diff --git a/config/main.rviz b/config/main.rviz index 10daa84f..fc0cef4d 100644 --- a/config/main.rviz +++ b/config/main.rviz @@ -4,9 +4,13 @@ Panels: Name: Displays Property Tree Widget: Expanded: + - /LaserScan1 + - /LaserScan1/Topic1 - /Camera1/Visibility1 + - /Map1 + - /Map1/Topic1 Splitter Ratio: 0.5 - Tree Height: 520 + Tree Height: 543 - Class: rviz_common/Selection Name: Selection - Class: rviz_common/Tool Properties @@ -46,6 +50,8 @@ Visualization Manager: Frame Timeout: 15 Frames: All Enabled: true + base_footprint: + Value: true base_link: Value: true camera_link: @@ -74,6 +80,8 @@ Visualization Manager: Tree: odom: base_link: + base_footprint: + {} chassis: camera_link: camera_link_optical: @@ -108,6 +116,10 @@ Visualization Manager: Expand Link Details: false Expand Tree: false Link Tree Style: Links in Alphabetic Order + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false base_link: Alpha: 1 Show Axes: false @@ -151,6 +163,9 @@ Visualization Manager: Show Axes: false Show Trail: false Value: true + Mass Properties: + Inertia: false + Mass: false Name: RobotModel TF Prefix: "" Update Interval: 0 @@ -182,15 +197,17 @@ Visualization Manager: Style: Flat Squares Topic: Depth: 5 - Durability Policy: Volatile + Durability Policy: Transient Local + Filter size: 10 History Policy: Keep Last - Reliability Policy: Reliable + Reliability Policy: Best Effort Value: /scan Use Fixed Frame: true Use rainbow: true Value: true - Class: rviz_default_plugins/Camera Enabled: true + Far Plane Distance: 100 Image Rendering: background and overlay Name: Camera Overlay Alpha: 0.5 @@ -204,10 +221,32 @@ Visualization Manager: Visibility: Grid: true LaserScan: true + Map: true RobotModel: false TF: false Value: true Zoom Factor: 1 + - Alpha: 0.699999988079071 + Class: rviz_default_plugins/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: + Depth: 5 + Durability Policy: Transient Local + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Best Effort + Value: /map + Update Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /map_updates + Use Timestamp: false + Value: true Enabled: true Global Options: Background Color: 48; 48; 48 @@ -223,6 +262,9 @@ Visualization Manager: - Class: rviz_default_plugins/Measure Line color: 128; 128; 0 - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 Topic: Depth: 5 Durability Policy: Volatile @@ -251,7 +293,7 @@ Visualization Manager: Views: Current: Class: rviz_default_plugins/Orbit - Distance: 5.735118865966797 + Distance: 2.1972548961639404 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 @@ -266,26 +308,26 @@ Visualization Manager: Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.32979676127433777 + Pitch: 0.22979654371738434 Target Frame: Value: Orbit (rviz) - Yaw: 5.1385817527771 + Yaw: 1.590415358543396 Saved: ~ Window Geometry: Camera: collapsed: false Displays: collapsed: false - Height: 996 + Height: 1016 Hide Left Dock: false Hide Right Dock: true - QMainWindow State: 000000ff00000000fd00000004000000000000016a00000385fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000004100000297000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006101000002de000000e80000002800ffffff000000010000010f00000386fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000004100000386000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d006501000000000000045000000000000000000000060e0000038500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd00000004000000000000016a0000039efc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002aa000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006101000002ed000000ee0000002800ffffff000000010000010f00000386fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000004100000386000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000005ca0000039e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Tool Properties: collapsed: false Views: collapsed: true - Width: 1918 - X: 0 - Y: 28 + Width: 1850 + X: 70 + Y: 27 diff --git a/config/my_controllers.yaml b/config/my_controllers.yaml index b07f970c..ecb7af13 100644 --- a/config/my_controllers.yaml +++ b/config/my_controllers.yaml @@ -15,7 +15,8 @@ diff_cont: publish_rate: 50.0 base_frame_id: base_link - + + left_wheel_names: ['left_wheel_joint'] right_wheel_names: ['right_wheel_joint'] wheel_separation: 0.297 diff --git a/config/nav2_params.yaml b/config/nav2_params.yaml index bae3aa36..5f4b08f6 100644 --- a/config/nav2_params.yaml +++ b/config/nav2_params.yaml @@ -26,7 +26,7 @@ amcl: recovery_alpha_fast: 0.0 recovery_alpha_slow: 0.0 resample_interval: 1 - robot_model_type: "differential" + robot_model_type: "nav2_amcl::DifferentialMotionModel" save_pose_rate: 0.5 sigma_hit: 0.2 tf_broadcast: true @@ -39,49 +39,72 @@ amcl: z_short: 0.05 scan_topic: scan -amcl_map_client: - ros__parameters: - use_sim_time: True - -amcl_rclcpp_node: - ros__parameters: - use_sim_time: True - bt_navigator: ros__parameters: use_sim_time: True global_frame: map robot_base_frame: base_link odom_topic: /odom - enable_groot_monitoring: True - groot_zmq_publisher_port: 1666 - groot_zmq_server_port: 1667 - default_bt_xml_filename: "navigate_w_replanning_and_recovery.xml" + bt_loop_duration: 10 + default_server_timeout: 20 + # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: + # 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. plugin_lib_names: - - nav2_compute_path_to_pose_action_bt_node - - nav2_follow_path_action_bt_node - - nav2_back_up_action_bt_node - - nav2_spin_action_bt_node - - nav2_wait_action_bt_node - - nav2_clear_costmap_service_bt_node - - nav2_is_stuck_condition_bt_node - - nav2_goal_reached_condition_bt_node - - nav2_goal_updated_condition_bt_node - - nav2_initial_pose_received_condition_bt_node - - nav2_reinitialize_global_localization_service_bt_node - - nav2_rate_controller_bt_node - - nav2_distance_controller_bt_node - - nav2_speed_controller_bt_node - - nav2_truncate_path_action_bt_node - - nav2_goal_updater_node_bt_node - - nav2_recovery_node_bt_node - - nav2_pipeline_sequence_bt_node - - nav2_round_robin_node_bt_node - - nav2_transform_available_condition_bt_node - - nav2_time_expired_condition_bt_node - - nav2_distance_traveled_condition_bt_node + - nav2_compute_path_to_pose_action_bt_node + - nav2_compute_path_through_poses_action_bt_node + - nav2_smooth_path_action_bt_node + - nav2_follow_path_action_bt_node + - nav2_spin_action_bt_node + - nav2_wait_action_bt_node + - nav2_assisted_teleop_action_bt_node + - nav2_back_up_action_bt_node + - nav2_drive_on_heading_bt_node + - nav2_clear_costmap_service_bt_node + - nav2_is_stuck_condition_bt_node + - nav2_goal_reached_condition_bt_node + - nav2_goal_updated_condition_bt_node + - nav2_globally_updated_goal_condition_bt_node + - nav2_is_path_valid_condition_bt_node + - nav2_initial_pose_received_condition_bt_node + - nav2_reinitialize_global_localization_service_bt_node + - nav2_rate_controller_bt_node + - nav2_distance_controller_bt_node + - nav2_speed_controller_bt_node + - nav2_truncate_path_action_bt_node + - nav2_truncate_path_local_action_bt_node + - nav2_goal_updater_node_bt_node + - nav2_recovery_node_bt_node + - nav2_pipeline_sequence_bt_node + - nav2_round_robin_node_bt_node + - nav2_transform_available_condition_bt_node + - nav2_time_expired_condition_bt_node + - nav2_path_expiring_timer_condition + - nav2_distance_traveled_condition_bt_node + - nav2_single_trigger_bt_node + - nav2_goal_updated_controller_bt_node + - nav2_is_battery_low_condition_bt_node + - nav2_navigate_through_poses_action_bt_node + - nav2_navigate_to_pose_action_bt_node + - nav2_remove_passed_goals_action_bt_node + - nav2_planner_selector_bt_node + - nav2_controller_selector_bt_node + - nav2_goal_checker_selector_bt_node + - nav2_controller_cancel_bt_node + - nav2_path_longer_on_approach_bt_node + - nav2_wait_cancel_bt_node + - nav2_spin_cancel_bt_node + - nav2_back_up_cancel_bt_node + - nav2_assisted_teleop_cancel_bt_node + - nav2_drive_on_heading_cancel_bt_node + - nav2_is_battery_charging_condition_bt_node -bt_navigator_rclcpp_node: +bt_navigator_navigate_through_poses_rclcpp_node: + ros__parameters: + use_sim_time: True + +bt_navigator_navigate_to_pose_rclcpp_node: ros__parameters: use_sim_time: True @@ -92,8 +115,9 @@ controller_server: min_x_velocity_threshold: 0.001 min_y_velocity_threshold: 0.5 min_theta_velocity_threshold: 0.001 + failure_tolerance: 0.3 progress_checker_plugin: "progress_checker" - goal_checker_plugin: "goal_checker" + goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker" controller_plugins: ["FollowPath"] # Progress checker parameters @@ -102,11 +126,16 @@ controller_server: required_movement_radius: 0.5 movement_time_allowance: 10.0 # Goal checker parameters - goal_checker: + #precise_goal_checker: + # plugin: "nav2_controller::SimpleGoalChecker" + # xy_goal_tolerance: 0.25 + # yaw_goal_tolerance: 0.25 + # stateful: True + general_goal_checker: + stateful: True plugin: "nav2_controller::SimpleGoalChecker" xy_goal_tolerance: 0.25 yaw_goal_tolerance: 0.25 - stateful: True # DWB parameters FollowPath: plugin: "dwb_core::DWBLocalPlanner" @@ -150,10 +179,6 @@ controller_server: RotateToGoal.slowing_factor: 5.0 RotateToGoal.lookahead_time: -1.0 -controller_server_rclcpp_node: - ros__parameters: - use_sim_time: True - local_costmap: local_costmap: ros__parameters: @@ -188,15 +213,14 @@ local_costmap: clearing: True marking: True data_type: "LaserScan" + raytrace_max_range: 3.0 + raytrace_min_range: 0.0 + obstacle_max_range: 2.5 + obstacle_min_range: 0.0 static_layer: + plugin: "nav2_costmap_2d::StaticLayer" map_subscribe_transient_local: True always_send_full_costmap: True - local_costmap_client: - ros__parameters: - use_sim_time: True - local_costmap_rclcpp_node: - ros__parameters: - use_sim_time: True global_costmap: global_costmap: @@ -220,6 +244,10 @@ global_costmap: clearing: True marking: True data_type: "LaserScan" + raytrace_max_range: 3.0 + raytrace_min_range: 0.0 + obstacle_max_range: 2.5 + obstacle_min_range: 0.0 static_layer: plugin: "nav2_costmap_2d::StaticLayer" map_subscribe_transient_local: True @@ -228,25 +256,21 @@ global_costmap: cost_scaling_factor: 3.0 inflation_radius: 0.55 always_send_full_costmap: True - global_costmap_client: - ros__parameters: - use_sim_time: True - global_costmap_rclcpp_node: - ros__parameters: - use_sim_time: True map_server: ros__parameters: use_sim_time: True - yaml_filename: "turtlebot3_world.yaml" + # Overridden in launch by the "map" launch configuration or provided default value. + # To use in yaml, remove the default "map" value in the tb3_simulation_launch.py file & provide full path to map below. + yaml_filename: "" map_saver: ros__parameters: use_sim_time: True - save_map_timeout: 5000 + save_map_timeout: 5.0 free_thresh_default: 0.25 occupied_thresh_default: 0.65 - map_subscribe_transient_local: False + map_subscribe_transient_local: True planner_server: ros__parameters: @@ -259,25 +283,35 @@ planner_server: use_astar: false allow_unknown: true -planner_server_rclcpp_node: +smoother_server: ros__parameters: use_sim_time: True + smoother_plugins: ["simple_smoother"] + simple_smoother: + plugin: "nav2_smoother::SimpleSmoother" + tolerance: 1.0e-10 + max_its: 1000 + do_refinement: True -recoveries_server: +behavior_server: ros__parameters: costmap_topic: local_costmap/costmap_raw footprint_topic: local_costmap/published_footprint cycle_frequency: 10.0 - recovery_plugins: ["spin", "back_up", "wait"] + behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"] spin: - plugin: "nav2_recoveries/Spin" - back_up: - plugin: "nav2_recoveries/BackUp" + plugin: "nav2_behaviors/Spin" + backup: + plugin: "nav2_behaviors/BackUp" + drive_on_heading: + plugin: "nav2_behaviors/DriveOnHeading" wait: - plugin: "nav2_recoveries/Wait" + plugin: "nav2_behaviors/Wait" + assisted_teleop: + plugin: "nav2_behaviors/AssistedTeleop" global_frame: odom robot_base_frame: base_link - transform_timeout: 0.1 + transform_tolerance: 0.1 use_sim_time: true simulate_ahead_time: 2.0 max_rotational_vel: 1.0 @@ -287,3 +321,29 @@ recoveries_server: robot_state_publisher: ros__parameters: use_sim_time: True + +waypoint_follower: + ros__parameters: + use_sim_time: True + loop_rate: 20 + stop_on_failure: false + waypoint_task_executor_plugin: "wait_at_waypoint" + wait_at_waypoint: + plugin: "nav2_waypoint_follower::WaitAtWaypoint" + enabled: True + waypoint_pause_duration: 200 + +velocity_smoother: + ros__parameters: + use_sim_time: True + smoothing_frequency: 20.0 + scale_velocities: False + feedback: "OPEN_LOOP" + max_velocity: [0.26, 0.0, 1.0] + min_velocity: [-0.26, 0.0, -1.0] + max_accel: [2.5, 0.0, 3.2] + max_decel: [-2.5, 0.0, -3.2] + odom_topic: "odom" + odom_duration: 0.1 + deadband_velocity: [0.0, 0.0, 0.0] + velocity_timeout: 1.0 diff --git a/description/ros2_control.xacro b/description/ros2_control.xacro index 296a7c57..d55f5de1 100644 --- a/description/ros2_control.xacro +++ b/description/ros2_control.xacro @@ -8,10 +8,10 @@ left_wheel_joint right_wheel_joint 30 - /dev/ttyUSB0 + /dev/ttyACM0 57600 1000 - 3436 + 2800 diff --git a/launch/launch_robot.launch.py b/launch/launch_robot.launch.py index 670d6ae5..01e4f4b7 100755 --- a/launch/launch_robot.launch.py +++ b/launch/launch_robot.launch.py @@ -61,7 +61,7 @@ def generate_launch_description(): diff_drive_spawner = Node( package="controller_manager", - executable="spawner.py", + executable="spawner", arguments=["diff_cont"], ) @@ -74,7 +74,7 @@ def generate_launch_description(): joint_broad_spawner = Node( package="controller_manager", - executable="spawner.py", + executable="spawner", arguments=["joint_broad"], ) diff --git a/launch/launch_sim.launch.py b/launch/launch_sim.launch.py index e08f9727..0db2f6e8 100755 --- a/launch/launch_sim.launch.py +++ b/launch/launch_sim.launch.py @@ -57,13 +57,13 @@ def generate_launch_description(): diff_drive_spawner = Node( package="controller_manager", - executable="spawner.py", + executable="spawner", arguments=["diff_cont"], ) joint_broad_spawner = Node( package="controller_manager", - executable="spawner.py", + executable="spawner", arguments=["joint_broad"], ) diff --git a/launch/navigation_launch.py b/launch/navigation_launch.py index 237d2095..d9f7cb5e 100644 --- a/launch/navigation_launch.py +++ b/launch/navigation_launch.py @@ -17,9 +17,12 @@ from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable -from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument, GroupAction, SetEnvironmentVariable +from launch.conditions import IfCondition +from launch.substitutions import LaunchConfiguration, PythonExpression +from launch_ros.actions import LoadComposableNodes from launch_ros.actions import Node +from launch_ros.descriptions import ComposableNode, ParameterFile from nav2_common.launch import RewrittenYaml @@ -31,14 +34,19 @@ def generate_launch_description(): use_sim_time = LaunchConfiguration('use_sim_time') autostart = LaunchConfiguration('autostart') params_file = LaunchConfiguration('params_file') - default_bt_xml_filename = LaunchConfiguration('default_bt_xml_filename') - map_subscribe_transient_local = LaunchConfiguration('map_subscribe_transient_local') + use_composition = LaunchConfiguration('use_composition') + container_name = LaunchConfiguration('container_name') + container_name_full = (namespace, '/', container_name) + use_respawn = LaunchConfiguration('use_respawn') + log_level = LaunchConfiguration('log_level') lifecycle_nodes = ['controller_server', + 'smoother_server', 'planner_server', - 'recoveries_server', + 'behavior_server', 'bt_navigator', - 'waypoint_follower'] + 'waypoint_follower', + 'velocity_smoother'] # Map fully qualified names to relative ones so the node's namespace can be prepended. # In case of the transforms (tf), currently, there doesn't seem to be a better alternative @@ -52,94 +60,213 @@ def generate_launch_description(): # Create our own temporary YAML files that include substitutions param_substitutions = { 'use_sim_time': use_sim_time, - 'default_bt_xml_filename': default_bt_xml_filename, - 'autostart': autostart, - 'map_subscribe_transient_local': map_subscribe_transient_local} + 'autostart': autostart} - configured_params = RewrittenYaml( + configured_params = ParameterFile( + RewrittenYaml( source_file=params_file, root_key=namespace, param_rewrites=param_substitutions, - convert_types=True) - - return LaunchDescription([ - # Set env var to print messages to stdout immediately - SetEnvironmentVariable('RCUTILS_LOGGING_BUFFERED_STREAM', '1'), - - DeclareLaunchArgument( - 'namespace', default_value='', - description='Top-level namespace'), - - DeclareLaunchArgument( - 'use_sim_time', default_value='false', - description='Use simulation (Gazebo) clock if true'), - - DeclareLaunchArgument( - 'autostart', default_value='true', - description='Automatically startup the nav2 stack'), - - DeclareLaunchArgument( - 'params_file', - default_value=os.path.join(bringup_dir, 'config', 'nav2_params.yaml'), - description='Full path to the ROS2 parameters file to use'), - - DeclareLaunchArgument( - 'default_bt_xml_filename', - default_value=os.path.join( - get_package_share_directory('nav2_bt_navigator'), - 'behavior_trees', 'navigate_w_replanning_and_recovery.xml'), - description='Full path to the behavior tree xml file to use'), - - DeclareLaunchArgument( - 'map_subscribe_transient_local', default_value='false', - description='Whether to set the map subscriber QoS to transient local'), - - Node( - package='nav2_controller', - executable='controller_server', - output='screen', - parameters=[configured_params], - remappings=remappings), - - Node( - package='nav2_planner', - executable='planner_server', - name='planner_server', - output='screen', - parameters=[configured_params], - remappings=remappings), - - Node( - package='nav2_recoveries', - executable='recoveries_server', - name='recoveries_server', - output='screen', - parameters=[configured_params], - remappings=remappings), - - Node( - package='nav2_bt_navigator', - executable='bt_navigator', - name='bt_navigator', - output='screen', - parameters=[configured_params], - remappings=remappings), - - Node( - package='nav2_waypoint_follower', - executable='waypoint_follower', - name='waypoint_follower', - output='screen', - parameters=[configured_params], - remappings=remappings), - - Node( - package='nav2_lifecycle_manager', - executable='lifecycle_manager', - name='lifecycle_manager_navigation', - output='screen', - parameters=[{'use_sim_time': use_sim_time}, - {'autostart': autostart}, - {'node_names': lifecycle_nodes}]), - - ]) + convert_types=True), + allow_substs=True) + + stdout_linebuf_envvar = SetEnvironmentVariable( + 'RCUTILS_LOGGING_BUFFERED_STREAM', '1') + + declare_namespace_cmd = DeclareLaunchArgument( + 'namespace', + default_value='', + description='Top-level namespace') + + declare_use_sim_time_cmd = DeclareLaunchArgument( + 'use_sim_time', + default_value='false', + description='Use simulation (Gazebo) clock if true') + + declare_params_file_cmd = DeclareLaunchArgument( + 'params_file', + default_value=os.path.join(bringup_dir, 'config', 'nav2_params.yaml'), + description='Full path to the ROS2 parameters file to use for all launched nodes') + + declare_autostart_cmd = DeclareLaunchArgument( + 'autostart', default_value='true', + description='Automatically startup the nav2 stack') + + declare_use_composition_cmd = DeclareLaunchArgument( + 'use_composition', default_value='False', + description='Use composed bringup if True') + + declare_container_name_cmd = DeclareLaunchArgument( + 'container_name', default_value='nav2_container', + description='the name of conatiner that nodes will load in if use composition') + + declare_use_respawn_cmd = DeclareLaunchArgument( + 'use_respawn', default_value='False', + description='Whether to respawn if a node crashes. Applied when composition is disabled.') + + declare_log_level_cmd = DeclareLaunchArgument( + 'log_level', default_value='info', + description='log level') + + load_nodes = GroupAction( + condition=IfCondition(PythonExpression(['not ', use_composition])), + actions=[ + Node( + package='nav2_controller', + executable='controller_server', + output='screen', + respawn=use_respawn, + respawn_delay=2.0, + parameters=[configured_params], + arguments=['--ros-args', '--log-level', log_level], + remappings=remappings + [('cmd_vel', 'cmd_vel_nav')]), + Node( + package='nav2_smoother', + executable='smoother_server', + name='smoother_server', + output='screen', + respawn=use_respawn, + respawn_delay=2.0, + parameters=[configured_params], + arguments=['--ros-args', '--log-level', log_level], + remappings=remappings), + Node( + package='nav2_planner', + executable='planner_server', + name='planner_server', + output='screen', + respawn=use_respawn, + respawn_delay=2.0, + parameters=[configured_params], + arguments=['--ros-args', '--log-level', log_level], + remappings=remappings), + Node( + package='nav2_behaviors', + executable='behavior_server', + name='behavior_server', + output='screen', + respawn=use_respawn, + respawn_delay=2.0, + parameters=[configured_params], + arguments=['--ros-args', '--log-level', log_level], + remappings=remappings), + Node( + package='nav2_bt_navigator', + executable='bt_navigator', + name='bt_navigator', + output='screen', + respawn=use_respawn, + respawn_delay=2.0, + parameters=[configured_params], + arguments=['--ros-args', '--log-level', log_level], + remappings=remappings), + Node( + package='nav2_waypoint_follower', + executable='waypoint_follower', + name='waypoint_follower', + output='screen', + respawn=use_respawn, + respawn_delay=2.0, + parameters=[configured_params], + arguments=['--ros-args', '--log-level', log_level], + remappings=remappings), + Node( + package='nav2_velocity_smoother', + executable='velocity_smoother', + name='velocity_smoother', + output='screen', + respawn=use_respawn, + respawn_delay=2.0, + parameters=[configured_params], + arguments=['--ros-args', '--log-level', log_level], + remappings=remappings + + [('cmd_vel', 'cmd_vel_nav'), ('cmd_vel_smoothed', 'cmd_vel')]), + Node( + package='nav2_lifecycle_manager', + executable='lifecycle_manager', + name='lifecycle_manager_navigation', + output='screen', + arguments=['--ros-args', '--log-level', log_level], + parameters=[{'use_sim_time': use_sim_time}, + {'autostart': autostart}, + {'node_names': lifecycle_nodes}]), + ] + ) + + load_composable_nodes = LoadComposableNodes( + condition=IfCondition(use_composition), + target_container=container_name_full, + composable_node_descriptions=[ + ComposableNode( + package='nav2_controller', + plugin='nav2_controller::ControllerServer', + name='controller_server', + parameters=[configured_params], + remappings=remappings + [('cmd_vel', 'cmd_vel_nav')]), + ComposableNode( + package='nav2_smoother', + plugin='nav2_smoother::SmootherServer', + name='smoother_server', + parameters=[configured_params], + remappings=remappings), + ComposableNode( + package='nav2_planner', + plugin='nav2_planner::PlannerServer', + name='planner_server', + parameters=[configured_params], + remappings=remappings), + ComposableNode( + package='nav2_behaviors', + plugin='behavior_server::BehaviorServer', + name='behavior_server', + parameters=[configured_params], + remappings=remappings), + ComposableNode( + package='nav2_bt_navigator', + plugin='nav2_bt_navigator::BtNavigator', + name='bt_navigator', + parameters=[configured_params], + remappings=remappings), + ComposableNode( + package='nav2_waypoint_follower', + plugin='nav2_waypoint_follower::WaypointFollower', + name='waypoint_follower', + parameters=[configured_params], + remappings=remappings), + ComposableNode( + package='nav2_velocity_smoother', + plugin='nav2_velocity_smoother::VelocitySmoother', + name='velocity_smoother', + parameters=[configured_params], + remappings=remappings + + [('cmd_vel', 'cmd_vel_nav'), ('cmd_vel_smoothed', 'cmd_vel')]), + ComposableNode( + package='nav2_lifecycle_manager', + plugin='nav2_lifecycle_manager::LifecycleManager', + name='lifecycle_manager_navigation', + parameters=[{'use_sim_time': use_sim_time, + 'autostart': autostart, + 'node_names': lifecycle_nodes}]), + ], + ) + + # Create the launch description and populate + ld = LaunchDescription() + + # Set environment variables + ld.add_action(stdout_linebuf_envvar) + + # Declare the launch options + ld.add_action(declare_namespace_cmd) + ld.add_action(declare_use_sim_time_cmd) + ld.add_action(declare_params_file_cmd) + ld.add_action(declare_autostart_cmd) + ld.add_action(declare_use_composition_cmd) + ld.add_action(declare_container_name_cmd) + ld.add_action(declare_use_respawn_cmd) + ld.add_action(declare_log_level_cmd) + # Add the actions to launch all of the navigation nodes + ld.add_action(load_nodes) + ld.add_action(load_composable_nodes) + + return ld diff --git a/launch/rplidar.launch.py b/launch/rplidar.launch.py index 40c9ddea..3c1b7009 100644 --- a/launch/rplidar.launch.py +++ b/launch/rplidar.launch.py @@ -7,11 +7,11 @@ def generate_launch_description(): return LaunchDescription([ Node( - package='rplidar_ros', - executable='rplidar_composition', + package='ydlidar_ros2_driver', + executable='ydlidar_ros2_driver_node', output='screen', parameters=[{ - 'serial_port': '/dev/serial/by-path/platform-fd500000.pcie-pci-0000:01:00.0-usb-0:1.3:1.0-port0', + 'serial_port': '/dev/serial/by-path/platform-fd500000.pcie-pci-0000:01:00.0-usb-0:1.2:1.0-port0', 'frame_id': 'laser_frame', 'angle_compensate': True, 'scan_mode': 'Standard' diff --git a/worlds/Hospital.world b/worlds/Hospital.world new file mode 100644 index 00000000..71809f30 --- /dev/null +++ b/worlds/Hospital.world @@ -0,0 +1,1384 @@ + + + + 1 + 0 0 10 0 -0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + 0 + 0 + 0 + + + + 1 + + + + + 0 0 1 + 100 100 + + + + + + 100 + 50 + + + + + + + + + + + 10 + + + 0 + + + 0 0 1 + 100 100 + + + + + + + 0 + 0 + 0 + + + 0 0 -9.8 + 6e-06 2.3e-05 -4.2e-05 + + + 0.001 + 1 + 1000 + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + 1 + + + + + EARTH_WGS84 + 0 + 0 + 0 + 0 + + + 0.157709 -0.122347 0 0 -0 0 + + + + + 3 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 3 0.15 2.5 + + + + + 1 0.764706 0.305882 1 + + + 0 + + + 6.145 -0.225 0 0 -0 1.5708 + 0 + 0 + 0 + + + + + + 2.25 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 2.25 0.15 2.5 + + + + + 1 0.764706 0.305882 1 + + + 0 + + + 6.145 2.25 0 0 -0 1.5708 + 0 + 0 + 0 + + + 2.345 3.3 0 0 -0 3.14159 + + -1.52457 0 1.25 0 -0 0 + + + 4.70086 0.15 2.5 + + + + + 1 0.764706 0.305882 1 + + + 0 + + + + + + 4.70086 0.15 2.5 + + + -1.52457 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 2.80043 0 1.25 0 -0 0 + + + 2.14914 0.15 2.5 + + + + + 1 0.764706 0.305882 1 + + + 0 + + + + + + 2.14914 0.15 2.5 + + + 2.80043 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 1.27586 0 2.25 0 -0 0 + + + 0.9 0.15 0.5 + + + + + 1 0.764706 0.305882 1 + + + 0 + + + + + + 0.9 0.15 0.5 + + + 1.27586 0 2.25 0 -0 0 + 10 + + + + + + + + + + + + + + 0 + 0 + 0 + + + + + + 4 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 4 0.15 2.5 + + + + + 1 0.470588 0 1 + + + 0 + + + -1.455 5.225 0 0 -0 1.5708 + 0 + 0 + 0 + + + + + + 2.5 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 2.5 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + -1.455 8.325 0 0 -0 1.5708 + 0 + 0 + 0 + + + -5.255 9.5 0 0 -0 3.14159 + + -1.31188 0 1.25 0 -0 0 + + + 5.12624 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + + + + 5.12624 0.15 2.5 + + + -1.31188 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 3.01312 0 1.25 0 -0 0 + + + 1.72376 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + + + + 1.72376 0.15 2.5 + + + 3.01312 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 1.70124 0 2.25 0 -0 0 + + + 0.9 0.15 0.5 + + + + + 1 1 1 1 + + + 0 + + + + + + 0.9 0.15 0.5 + + + 1.70124 0 2.25 0 -0 0 + 10 + + + + + + + + + + + + + + 0 + 0 + 0 + + + + + + 7 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 7 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + -9.055 6.075 0 0 -0 -1.5708 + 0 + 0 + 0 + + + + + + 12.25 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 12.25 0.15 2.5 + + + + + 1 0.470588 0 1 + + + 0 + + + -9.055 -3.4 0 0 -0 -1.5708 + 0 + 0 + 0 + + + + + + 18.25 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 18.25 0.15 2.5 + + + + + 1 0.764706 0.305882 1 + + + 0 + + + -0.005 -9.45 0 0 -0 0 + 0 + 0 + 0 + + + + + + 0.16 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 0.16 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 9.05 -9.45 0 0 -0 0 + 0 + 0 + 0 + + + + + + 13.5 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 13.5 0.15 2.5 + + + + + 1 0.764706 0.305882 1 + + + 0 + + + 9.055 -2.775 0 0 -0 1.5708 + 0 + 0 + 0 + + + + + + 4.5 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 4.5 0.15 2.5 + + + + + 1 0.764706 0.305882 1 + + + 0 + + + 9.055 6.075 0 0 -0 1.5708 + 0 + 0 + 0 + + + + + + 10.5 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 10.5 0.15 2.5 + + + + + 1 0.764706 0.305882 1 + + + 0 + + + 3.88 8.25 0 0 -0 3.14159 + 0 + 0 + 0 + + + + + + 8 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 8 0.15 2.5 + + + + + 1 0.470588 0 1 + + + 0 + + + -4.705 -5.575 0 0 -0 -1.5708 + 0 + 0 + 0 + + + 6.145 -5.575 0 0 -0 -1.5708 + + -1.89375 0 1.25 0 -0 0 + + + 4.21249 0.15 2.5 + + + + + 1 0.764706 0.305882 1 + + + 0 + + + + + + 4.21249 0.15 2.5 + + + -1.89375 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 2.55625 0 1.25 0 -0 0 + + + 2.88751 0.15 2.5 + + + + + 1 0.764706 0.305882 1 + + + 0 + + + + + + 2.88751 0.15 2.5 + + + 2.55625 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0.662493 0 2.25 0 -0 0 + + + 0.9 0.15 0.5 + + + + + 1 0.764706 0.305882 1 + + + 0 + + + + + + 0.9 0.15 0.5 + + + 0.662493 0 2.25 0 -0 0 + 10 + + + + + + + + + + + + + + 0 + 0 + 0 + + + 7.55099 -0.189385 0 0 -0 0 + + -1.05943 0 1.25 0 -0 0 + + + 0.881145 0.15 2.5 + + + + + 1 0.764706 0.305882 1 + + + 0 + + + + + + 0.881145 0.15 2.5 + + + -1.05943 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0.890573 0 1.25 0 -0 0 + + + 1.21886 0.15 2.5 + + + + + 1 0.764706 0.305882 1 + + + 0 + + + + + + 1.21886 0.15 2.5 + + + 0.890573 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + -0.168855 0 2.25 0 -0 0 + + + 0.9 0.15 0.5 + + + + + 1 0.764706 0.305882 1 + + + 0 + + + + + + 0.9 0.15 0.5 + + + -0.168855 0 2.25 0 -0 0 + 10 + + + + + + + + + + + + + + 0 + 0 + 0 + + + 0.72 -1.65 0 0 -0 0 + + -3.10996 0 1.25 0 -0 0 + + + 4.78008 0.15 2.5 + + + + + 1 0.470588 0 1 + + + 0 + + + + + + 4.78008 0.15 2.5 + + + -3.10996 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 2.84004 0 1.25 0 -0 0 + + + 5.31992 0.15 2.5 + + + + + 1 0.470588 0 1 + + + 0 + + + + + + 5.31992 0.15 2.5 + + + 2.84004 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + -0.269924 0 2.25 0 -0 0 + + + 0.9 0.15 0.5 + + + + + 1 0.470588 0 1 + + + 0 + + + + + + 0.9 0.15 0.5 + + + -0.269924 0 2.25 0 -0 0 + 10 + + + + + + + + + + + + + + 0 + 0 + 0 + + 1 + + + 58 712000000 + 59 315814015 + 1717246985 613538408 + 58712 + + 0 0 0 0 -0 0 + 1 1 1 + + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0.157709 -0.122347 0 0 -0 0 + 1 1 1 + + 6.30271 -0.347347 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + 6.30271 2.12765 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + 2.50271 3.17765 0 0 -0 3.14159 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + -1.29729 5.10265 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + -1.29729 8.20265 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + -5.09729 9.37765 0 0 -0 3.14159 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + -8.89729 5.95265 0 0 0 -1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + -8.89729 -3.52235 0 0 0 -1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + 0.152709 -9.57235 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + 9.20771 -9.57235 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + 9.21271 -2.89735 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + 9.21271 5.95265 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + 4.03771 8.12765 0 0 -0 3.14159 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + -4.54729 -5.69735 0 0 0 -1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + 6.30271 -5.69735 0 0 0 -1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + 7.7087 -0.311732 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + 0.877709 -1.77235 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 10 0 -0 0 + + + + + 29.8147 -20.2933 9.15383 0 0.275643 2.35619 + orbit + perspective + + + +