Skip to content

Commit 0db5f07

Browse files
authored
[loopback_sim] Publish clock, [nav2_costmap_2d] Fix Qos (#4726)
* Publish /clock from loopback sim Signed-off-by: Adi Vardi <adi.vardi@enway.ai> * [nav2_costmap_2d] Fix obstacle_layer trying to use RELIABLE QoS Use QoS profile from rclcpp::SensorDataQoS() instead of rmw_qos_profile_t. This solves an issue where the subscriber uses RELIABLE setting even when initialized from rmw_qos_profile_sensor_data. In addition the Subscriber(..., rmw_qos_profile_t) constructor is deprecated in favor of Subscriber(..., rclcpp::QoS) Signed-off-by: Adi Vardi <adi.vardi@enway.ai> * [nav2_smac_planner] fix typos Signed-off-by: Adi Vardi <adi.vardi@enway.ai> * Use single quotes Signed-off-by: Adi Vardi <adi.vardi@enway.ai> --------- Signed-off-by: Adi Vardi <adi.vardi@enway.ai>
1 parent 44a69cc commit 0db5f07

File tree

4 files changed

+37
-21
lines changed

4 files changed

+37
-21
lines changed

nav2_costmap_2d/plugins/obstacle_layer.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -225,8 +225,7 @@ void ObstacleLayer::onInitialize()
225225
source.c_str(), topic.c_str(),
226226
global_frame_.c_str(), expected_update_rate, observation_keep_time);
227227

228-
rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_sensor_data;
229-
custom_qos_profile.depth = 50;
228+
const auto custom_qos_profile = rclcpp::SensorDataQoS().keep_last(50);
230229

231230
// create a callback for the topic
232231
if (data_type == "LaserScan") {

nav2_loopback_sim/README.md

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@ This was created by Steve Macenski of [Open Navigation LLC](https://opennav.org)
88

99
It is drop-in replacable with AMR simulators and global localization by providing:
1010
- Map -> Odom transform
11-
- Odom -> Base Link transform, `nav_msgs/Odometry` odometry
11+
- Odom -> Base Link transform, `nav_msgs/Odometry` odometry
1212
- Accepts the standard `/initialpose` topic for transporting the robot to another location
1313

1414
Note: This does not provide sensor data, so it is required that the global (and probably local) costmap contain the `StaticLayer` to avoid obstacles.
@@ -33,12 +33,15 @@ ros2 launch nav2_bringup tb4_loopback_simulation.launch.py # Nav2 integrated na
3333

3434
### Parameters
3535

36-
- `update_duration`: the duration between updates (default 0.01 -- 100hz)
36+
- `update_duration`: The duration between updates (default 0.01 -- 100hz)
3737
- `base_frame_id`: The base frame to use (default `base_link`)
3838
- `odom_frame_id`: The odom frame to use (default `odom`)
3939
- `map_frame_id`: The map frame to use (default `map`)
4040
- `scan_frame_id`: The can frame to use to publish a scan to keep the collision monitor fed and happy (default `base_scan` for TB3, `rplidar_link` for TB4)
4141
- `enable_stamped_cmd_vel`: Whether cmd_vel is stamped or unstamped (i.e. Twist or TwistStamped). Default `false` for `Twist`.
42+
- `scan_publish_dur`: : The duration between publishing scan (default 0.1s -- 10hz)
43+
- `publish_map_odom_tf`: Whether or not to publish tf from `map_frame_id` to `odom_frame_id` (default `true`)
44+
- `publish_clock`: Whether or not to publish simulated clock to `/clock` (default `true`)
4245

4346
### Topics
4447

@@ -47,6 +50,7 @@ This node subscribes to:
4750
- `cmd_vel`: Nav2's output twist to get the commanded velocity
4851

4952
This node publishes:
53+
- `clock`: To publish a simulation clock for all other nodes with `use_sim_time=True`
5054
- `odom`: To publish odometry from twist
5155
- `tf`: To publish map->odom and odom->base_link transforms
52-
- `scan`: To publish a bogus max range laser scan sensor to make the collision monitor happy
56+
- `scan`: To publish a range laser scan sensor based on the static map

nav2_loopback_sim/nav2_loopback_sim/loopback_simulator.py

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
from rclpy.duration import Duration
2525
from rclpy.node import Node
2626
from rclpy.qos import DurabilityPolicy, QoSProfile, ReliabilityPolicy
27+
from rosgraph_msgs.msg import Clock
2728
from sensor_msgs.msg import LaserScan
2829
from tf2_ros import Buffer, TransformBroadcaster, TransformListener
2930
import tf_transformations
@@ -84,6 +85,9 @@ def __init__(self):
8485
self.publish_map_odom_tf = self.get_parameter(
8586
'publish_map_odom_tf').get_parameter_value().bool_value
8687

88+
self.declare_parameter('publish_clock', True)
89+
self.publish_clock = self.get_parameter('publish_clock').get_parameter_value().bool_value
90+
8791
self.t_map_to_odom = TransformStamped()
8892
self.t_map_to_odom.header.frame_id = self.map_frame_id
8993
self.t_map_to_odom.child_frame_id = self.odom_frame_id
@@ -112,6 +116,10 @@ def __init__(self):
112116
depth=10)
113117
self.scan_pub = self.create_publisher(LaserScan, 'scan', sensor_qos)
114118

119+
if self.publish_clock:
120+
self.clock_timer = self.create_timer(0.1, self.clockTimerCallback)
121+
self.clock_pub = self.create_publisher(Clock, '/clock', 10)
122+
115123
self.setupTimer = self.create_timer(0.1, self.setupTimerCallback)
116124

117125
self.map_client = self.create_client(GetMap, '/map_server/map')
@@ -139,6 +147,11 @@ def setupTimerCallback(self):
139147
if self.mat_base_to_laser is None:
140148
self.getBaseToLaserTf()
141149

150+
def clockTimerCallback(self):
151+
msg = Clock()
152+
msg.clock = self.get_clock().now().to_msg()
153+
self.clock_pub.publish(msg)
154+
142155
def cmdVelCallback(self, msg):
143156
self.debug('Received cmd_vel')
144157
if self.initial_pose is None:

0 commit comments

Comments
 (0)