Skip to content

Commit

Permalink
adding default collision monitor to bringup (ros-navigation#3989)
Browse files Browse the repository at this point in the history
* adding default collision monitor to bringup

* Update nav2_multirobot_params_1.yaml

* adding to system test files

* adjust  for test
  • Loading branch information
SteveMacenski authored Nov 28, 2023
1 parent 6d2278e commit c1e4a42
Show file tree
Hide file tree
Showing 9 changed files with 270 additions and 3 deletions.
25 changes: 22 additions & 3 deletions nav2_bringup/launch/navigation_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,9 +45,10 @@ def generate_launch_description():
'smoother_server',
'planner_server',
'behavior_server',
'velocity_smoother',
'collision_monitor',
'bt_navigator',
'waypoint_follower',
'velocity_smoother',
]

# Map fully qualified names to relative ones so the node's namespace can be prepended.
Expand Down Expand Up @@ -198,7 +199,18 @@ def generate_launch_description():
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings
+ [('cmd_vel', 'cmd_vel_nav'), ('cmd_vel_smoothed', 'cmd_vel')],
+ [('cmd_vel', 'cmd_vel_nav')],
),
Node(
package='nav2_collision_monitor',
executable='collision_monitor',
name='collision_monitor',
output='screen',
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings,
),
Node(
package='nav2_lifecycle_manager',
Expand Down Expand Up @@ -266,7 +278,14 @@ def generate_launch_description():
name='velocity_smoother',
parameters=[configured_params],
remappings=remappings
+ [('cmd_vel', 'cmd_vel_nav'), ('cmd_vel_smoothed', 'cmd_vel')],
+ [('cmd_vel', 'cmd_vel_nav')],
),
ComposableNode(
package='nav2_collision_monitor',
plugin='nav2_collision_monitor::CollisionMonitor',
name='collision_monitor',
parameters=[configured_params],
remappings=remappings,
),
ComposableNode(
package='nav2_lifecycle_manager',
Expand Down
31 changes: 31 additions & 0 deletions nav2_bringup/params/nav2_multirobot_params_1.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -285,3 +285,34 @@ waypoint_follower:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
enabled: True
waypoint_pause_duration: 200

collision_monitor:
ros__parameters:
base_frame_id: "base_footprint"
odom_frame_id: "odom"
cmd_vel_in_topic: "cmd_vel_smoothed"
cmd_vel_out_topic: "cmd_vel"
state_topic: "collision_monitor_state"
transform_tolerance: 0.2
source_timeout: 1.0
base_shift_correction: True
stop_pub_timeout: 2.0
# Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types,
# and robot footprint for "approach" action type.
polygons: ["FootprintApproach"]
FootprintApproach:
type: "polygon"
action_type: "approach"
footprint_topic: "local_costmap/published_footprint"
time_before_collision: 2.0
simulation_time_step: 0.1
min_points: 6
visualize: False
enabled: True
observation_sources: ["scan"]
scan:
type: "scan"
topic: "/robot1/scan"
min_height: 0.15
max_height: 2.0
enabled: True
31 changes: 31 additions & 0 deletions nav2_bringup/params/nav2_multirobot_params_2.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -284,3 +284,34 @@ waypoint_follower:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
enabled: True
waypoint_pause_duration: 200

collision_monitor:
ros__parameters:
base_frame_id: "base_footprint"
odom_frame_id: "odom"
cmd_vel_in_topic: "cmd_vel_smoothed"
cmd_vel_out_topic: "cmd_vel"
state_topic: "collision_monitor_state"
transform_tolerance: 0.2
source_timeout: 1.0
base_shift_correction: True
stop_pub_timeout: 2.0
# Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types,
# and robot footprint for "approach" action type.
polygons: ["FootprintApproach"]
FootprintApproach:
type: "polygon"
action_type: "approach"
footprint_topic: "local_costmap/published_footprint"
time_before_collision: 2.0
simulation_time_step: 0.1
min_points: 6
visualize: False
enabled: True
observation_sources: ["scan"]
scan:
type: "scan"
topic: "/robot2/scan"
min_height: 0.15
max_height: 2.0
enabled: True
31 changes: 31 additions & 0 deletions nav2_bringup/params/nav2_multirobot_params_all.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -346,3 +346,34 @@ velocity_smoother:
odom_duration: 0.1
deadband_velocity: [0.0, 0.0, 0.0]
velocity_timeout: 1.0

collision_monitor:
ros__parameters:
base_frame_id: "base_footprint"
odom_frame_id: "odom"
cmd_vel_in_topic: "cmd_vel_smoothed"
cmd_vel_out_topic: "cmd_vel"
state_topic: "collision_monitor_state"
transform_tolerance: 0.2
source_timeout: 1.0
base_shift_correction: True
stop_pub_timeout: 2.0
# Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types,
# and robot footprint for "approach" action type.
polygons: ["FootprintApproach"]
FootprintApproach:
type: "polygon"
action_type: "approach"
footprint_topic: "/local_costmap/published_footprint"
time_before_collision: 2.0
simulation_time_step: 0.1
min_points: 6
visualize: False
enabled: True
observation_sources: ["scan"]
scan:
type: "scan"
topic: "<robot_namespace>/scan"
min_height: 0.15
max_height: 2.0
enabled: True
31 changes: 31 additions & 0 deletions nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -343,3 +343,34 @@ velocity_smoother:
odom_duration: 0.1
deadband_velocity: [0.0, 0.0, 0.0]
velocity_timeout: 1.0

collision_monitor:
ros__parameters:
base_frame_id: "base_footprint"
odom_frame_id: "odom"
cmd_vel_in_topic: "cmd_vel_smoothed"
cmd_vel_out_topic: "cmd_vel"
state_topic: "collision_monitor_state"
transform_tolerance: 0.2
source_timeout: 1.0
base_shift_correction: True
stop_pub_timeout: 2.0
# Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types,
# and robot footprint for "approach" action type.
polygons: ["FootprintApproach"]
FootprintApproach:
type: "polygon"
action_type: "approach"
footprint_topic: "/local_costmap/published_footprint"
time_before_collision: 2.0
simulation_time_step: 0.1
min_points: 6
visualize: False
enabled: True
observation_sources: ["scan"]
scan:
type: "scan"
topic: "scan"
min_height: 0.15
max_height: 2.0
enabled: True
31 changes: 31 additions & 0 deletions nav2_system_tests/src/costmap_filters/keepout_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -307,3 +307,34 @@ filter_mask_server:
frame_id: "map"
topic_name: "/filter_mask"
yaml_filename: "keepout_mask.yaml"

collision_monitor:
ros__parameters:
base_frame_id: "base_footprint"
odom_frame_id: "odom"
cmd_vel_in_topic: "cmd_vel_smoothed"
cmd_vel_out_topic: "cmd_vel"
state_topic: "collision_monitor_state"
transform_tolerance: 0.2
source_timeout: 1.0
base_shift_correction: True
stop_pub_timeout: 2.0
# Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types,
# and robot footprint for "approach" action type.
polygons: ["FootprintApproach"]
FootprintApproach:
type: "polygon"
action_type: "approach"
footprint_topic: "/local_costmap/published_footprint"
time_before_collision: 2.0
simulation_time_step: 0.1
min_points: 6
visualize: False
enabled: True
observation_sources: ["scan"]
scan:
type: "scan"
topic: "scan"
min_height: 0.15
max_height: 2.0
enabled: True
31 changes: 31 additions & 0 deletions nav2_system_tests/src/costmap_filters/speed_global_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -298,3 +298,34 @@ filter_mask_server:
frame_id: "map"
topic_name: "/filter_mask"
yaml_filename: "speed_mask.yaml"

collision_monitor:
ros__parameters:
base_frame_id: "base_footprint"
odom_frame_id: "odom"
cmd_vel_in_topic: "cmd_vel_smoothed"
cmd_vel_out_topic: "cmd_vel"
state_topic: "collision_monitor_state"
transform_tolerance: 0.2
source_timeout: 1.0
base_shift_correction: True
stop_pub_timeout: 2.0
# Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types,
# and robot footprint for "approach" action type.
polygons: ["FootprintApproach"]
FootprintApproach:
type: "polygon"
action_type: "approach"
footprint_topic: "/local_costmap/published_footprint"
time_before_collision: 2.0
simulation_time_step: 0.1
min_points: 6
visualize: False
enabled: True
observation_sources: ["scan"]
scan:
type: "scan"
topic: "scan"
min_height: 0.15
max_height: 2.0
enabled: True
31 changes: 31 additions & 0 deletions nav2_system_tests/src/costmap_filters/speed_local_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -298,3 +298,34 @@ filter_mask_server:
frame_id: "map"
topic_name: "/filter_mask"
yaml_filename: "speed_mask.yaml"

collision_monitor:
ros__parameters:
base_frame_id: "base_footprint"
odom_frame_id: "odom"
cmd_vel_in_topic: "cmd_vel_smoothed"
cmd_vel_out_topic: "cmd_vel"
state_topic: "collision_monitor_state"
transform_tolerance: 0.2
source_timeout: 1.0
base_shift_correction: True
stop_pub_timeout: 2.0
# Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types,
# and robot footprint for "approach" action type.
polygons: ["FootprintApproach"]
FootprintApproach:
type: "polygon"
action_type: "approach"
footprint_topic: "/local_costmap/published_footprint"
time_before_collision: 2.0
simulation_time_step: 0.1
min_points: 6
visualize: False
enabled: True
observation_sources: ["scan"]
scan:
type: "scan"
topic: "scan"
min_height: 0.15
max_height: 2.0
enabled: True
31 changes: 31 additions & 0 deletions nav2_system_tests/src/gps_navigation/nav2_no_map_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -306,3 +306,34 @@ velocity_smoother:
odom_duration: 0.1
deadband_velocity: [0.0, 0.0, 0.0]
velocity_timeout: 1.0

collision_monitor:
ros__parameters:
base_frame_id: "base_link"
odom_frame_id: "odom"
cmd_vel_in_topic: "cmd_vel_smoothed"
cmd_vel_out_topic: "cmd_vel"
state_topic: "collision_monitor_state"
transform_tolerance: 0.2
source_timeout: 1.0
base_shift_correction: True
stop_pub_timeout: 2.0
# Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types,
# and robot footprint for "approach" action type.
polygons: ["FootprintApproach"]
FootprintApproach:
type: "polygon"
action_type: "approach"
footprint_topic: "/local_costmap/published_footprint"
time_before_collision: 2.0
simulation_time_step: 0.1
min_points: 6
visualize: False
enabled: True
observation_sources: ["scan"]
scan:
type: "scan"
topic: "scan"
min_height: 0.15
max_height: 2.0
enabled: True

0 comments on commit c1e4a42

Please sign in to comment.