diff --git a/nav2_bringup/bringup/launch/multi_tb3_simulation_launch.py b/nav2_bringup/bringup/launch/multi_tb3_simulation_launch.py index dd13fae8bbd..bad21ce1240 100644 --- a/nav2_bringup/bringup/launch/multi_tb3_simulation_launch.py +++ b/nav2_bringup/bringup/launch/multi_tb3_simulation_launch.py @@ -102,7 +102,8 @@ def generate_launch_description(): # Start Gazebo with plugin providing the robot spawing service start_gazebo_cmd = ExecuteProcess( - cmd=[simulator, '--verbose', '-s', 'libgazebo_ros_factory.so', world], + cmd=[simulator, '--verbose', '-s', 'libgazebo_ros_init.so', + '-s', 'libgazebo_ros_factory.so', world], output='screen') # Define commands for spawing the robots into Gazebo diff --git a/nav2_bringup/bringup/launch/tb3_simulation_launch.py b/nav2_bringup/bringup/launch/tb3_simulation_launch.py index 5fad6db3f8a..675b6056980 100644 --- a/nav2_bringup/bringup/launch/tb3_simulation_launch.py +++ b/nav2_bringup/bringup/launch/tb3_simulation_launch.py @@ -131,7 +131,7 @@ def generate_launch_description(): # Specify the actions start_gazebo_server_cmd = ExecuteProcess( condition=IfCondition(use_simulator), - cmd=['gzserver', '-s', 'libgazebo_ros_init.so', world], + cmd=['gzserver', '-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so', world], cwd=[launch_dir], output='screen') start_gazebo_client_cmd = ExecuteProcess( diff --git a/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml b/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml index 2c0d414abd9..f90053c032c 100644 --- a/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml +++ b/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml @@ -59,6 +59,10 @@ bt_navigator: # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2. + # if enable_groot_monitoring is set to True, ports need to be different for each robot !! + enable_groot_monitoring: False + groot_zmq_publisher_port: 1666 + groot_zmq_server_port: 1667 plugin_lib_names: - nav2_compute_path_to_pose_action_bt_node - nav2_compute_path_through_poses_action_bt_node diff --git a/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml b/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml index 9f671b246a3..dfb6ab4520c 100644 --- a/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml +++ b/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml @@ -59,6 +59,10 @@ bt_navigator: # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2. + # if enable_groot_monitoring is set to True, ports need to be different for each robot !! + enable_groot_monitoring: False + groot_zmq_publisher_port: 1789 + groot_zmq_server_port: 1887 plugin_lib_names: - nav2_compute_path_to_pose_action_bt_node - nav2_compute_path_through_poses_action_bt_node diff --git a/nav2_bringup/nav2_gazebo_spawner/nav2_gazebo_spawner/nav2_gazebo_spawner.py b/nav2_bringup/nav2_gazebo_spawner/nav2_gazebo_spawner/nav2_gazebo_spawner.py index 9f4daaf196c..f8f79f61b0c 100644 --- a/nav2_bringup/nav2_gazebo_spawner/nav2_gazebo_spawner/nav2_gazebo_spawner.py +++ b/nav2_bringup/nav2_gazebo_spawner/nav2_gazebo_spawner/nav2_gazebo_spawner.py @@ -37,7 +37,8 @@ def main(): parser.add_argument('-z', type=float, default=0, help='the z component of the initial position [meters]') parser.add_argument('-k', '--timeout', type=float, default=10.0, - help="Seconds to wait. Block until the future is complete if negative. Don't wait if 0.") + help="Seconds to wait. Block until the future is complete if negative. \ + Don't wait if 0.") group = parser.add_mutually_exclusive_group(required=True) group.add_argument('-t', '--turtlebot_type', type=str,