diff --git a/c300/c300_bringup/launch/gazebo_c300.launch.py b/c300/c300_bringup/launch/gazebo_c300.launch.py index 9e4cf5c..f60a613 100644 --- a/c300/c300_bringup/launch/gazebo_c300.launch.py +++ b/c300/c300_bringup/launch/gazebo_c300.launch.py @@ -190,8 +190,11 @@ def generate_launch_description(): [FindPackageShare("ros_gz_sim"), "/launch/gz_sim.launch.py"] ), # TODO (marqrazz): fix the hardcoded path to the gazebo world + # -v is the verbose level + # 0: No output, 1: Error, 2: Error and warning, 3: Error, warning, and info, 4: Error, warning, info, and debug. + # -s launches Gazebo headless launch_arguments={ - "gz_args": " -r -v 3 /root/c3pzero_ws/src/c3pzero/c300/c300_bringup/worlds/depot.sdf" + "gz_args": " -r -v 3 -s /root/c3pzero_ws/src/c3pzero/c300/c300_bringup/worlds/depot.sdf" }.items(), condition=IfCondition(sim_ignition), ) diff --git a/c300/c300_navigation/launch/navigation.launch.py b/c300/c300_navigation/launch/navigation.launch.py index 760310e..eb304b3 100644 --- a/c300/c300_navigation/launch/navigation.launch.py +++ b/c300/c300_navigation/launch/navigation.launch.py @@ -81,7 +81,7 @@ def generate_launch_description(): declare_params_file_cmd = DeclareLaunchArgument( "params_file", - default_value=os.path.join(c300_nav_dir, "params", "nav2_params.yaml"), + default_value=os.path.join(c300_nav_dir, "params", "nav2_params_mppi.yaml"), description="Full path to the ROS2 parameters file to use for all launched nodes", ) diff --git a/c300/c300_navigation/params/nav2_params.yaml b/c300/c300_navigation/params/nav2_params_dwb.yaml similarity index 100% rename from c300/c300_navigation/params/nav2_params.yaml rename to c300/c300_navigation/params/nav2_params_dwb.yaml diff --git a/c300/c300_navigation/params/nav2_params_mppi.yaml b/c300/c300_navigation/params/nav2_params_mppi.yaml new file mode 100644 index 0000000..9250103 --- /dev/null +++ b/c300/c300_navigation/params/nav2_params_mppi.yaml @@ -0,0 +1,399 @@ +amcl: + ros__parameters: + use_sim_time: True + alpha1: 0.2 + alpha2: 0.2 + alpha3: 0.2 + alpha4: 0.2 + alpha5: 0.2 + base_frame_id: "base_footprint" + beam_skip_distance: 0.5 + beam_skip_error_threshold: 0.9 + beam_skip_threshold: 0.3 + do_beamskip: false + global_frame_id: "map" + lambda_short: 0.1 + laser_likelihood_max_dist: 2.0 + laser_max_range: 30.0 + laser_min_range: -1.0 + laser_model_type: "likelihood_field" + max_beams: 60 + max_particles: 2000 + min_particles: 500 + odom_frame_id: "odom" + pf_err: 0.05 + pf_z: 0.99 + recovery_alpha_fast: 0.0 + recovery_alpha_slow: 0.0 + resample_interval: 1 + robot_model_type: "nav2_amcl::DifferentialMotionModel" + save_pose_rate: 0.5 + sigma_hit: 0.2 + tf_broadcast: true + transform_tolerance: 1.0 + update_min_a: 0.2 + update_min_d: 0.25 + z_hit: 0.5 + z_max: 0.05 + z_rand: 0.5 + z_short: 0.05 + scan_topic: scan + set_initial_pose: true # this is currently setup for simulation + initial_pose: + x: 0.0 + y: 0.0 + yaw: 0.0 + +bt_navigator: + ros__parameters: + use_sim_time: True + global_frame: map + robot_base_frame: base_link + odom_topic: /odom + default_bt_xml_filename: "navigate_w_replanning_and_recovery.xml" + bt_loop_duration: 10 + default_server_timeout: 20 + enable_groot_monitoring: True + 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 + - nav2_smooth_path_action_bt_node + - nav2_follow_path_action_bt_node + - nav2_spin_action_bt_node + - nav2_wait_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_drive_on_heading_cancel_bt_node + +controller_server: + ros__parameters: + use_sim_time: True + controller_frequency: 30.0 + 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_plugins: ["general_goal_checker"] # "precise_goal_checker" + controller_plugins: ["FollowPath"] + + # Progress checker parameters + progress_checker: + plugin: "nav2_controller::SimpleProgressChecker" + required_movement_radius: 0.5 + movement_time_allowance: 10.0 + + general_goal_checker: + stateful: True + plugin: "nav2_controller::SimpleGoalChecker" + xy_goal_tolerance: 0.15 + yaw_goal_tolerance: 0.15 + + FollowPath: + plugin: "nav2_mppi_controller::MPPIController" + # inceased time_steps, prune_distance and reduced batch_size to attempt to drive vehicle at 1m/s + # vx_std increase was required to make the vehicle actually drive faster + # as you decrease wz_std it makes the vehile drive better in a straight line but makes it not want to turn around when given goals behind its current pose + # unknown why vy_max and vy_std are set for a diff drive vehicle + time_steps: 65 + model_dt: 0.05 + batch_size: 1500 + vx_std: 0.4 + vy_std: 0.2 + wz_std: 0.3 + vx_max: 1.0 + vx_min: -0.5 + vy_max: 0.5 + wz_max: 1.9 + iteration_count: 1 + prune_distance: 2.5 + transform_tolerance: 0.1 + temperature: 0.3 + gamma: 0.015 + motion_model: "DiffDrive" + visualize: false + reset_period: 1.0 # (only in Humble) + regenerate_noises: false + TrajectoryVisualizer: + trajectory_step: 5 + time_step: 3 + AckermannConstraints: + min_turning_r: 0.2 + critics: ["ConstraintCritic", "ObstaclesCritic", "GoalCritic", "GoalAngleCritic", "PathAlignCritic", "PathFollowCritic", "PathAngleCritic", "PreferForwardCritic"] + ConstraintCritic: + enabled: true + cost_power: 1 + cost_weight: 4.0 + GoalCritic: + enabled: true + cost_power: 1 + cost_weight: 5.0 + threshold_to_consider: 1.4 + GoalAngleCritic: + enabled: true + cost_power: 1 + cost_weight: 3.0 + threshold_to_consider: 0.5 + PreferForwardCritic: + # increased cost_power to 2 to force vehicle to drive forwards along long paths after increasing max speed + # - this causes failures when operating in a narrow workspace and would crash the vehicle by forcing it to turn around when it can't! + # increased threshold_to_consider to allow vehicle to back up over short distances + enabled: true + cost_power: 2 + cost_weight: 4.0 + threshold_to_consider: 2.0 + ObstaclesCritic: + enabled: true + cost_power: 1 + repulsion_weight: 1.5 + critical_weight: 20.0 + consider_footprint: false + collision_cost: 10000.0 + collision_margin_distance: 0.1 + near_goal_distance: 0.5 + inflation_radius: 0.55 # (only in Humble) + cost_scaling_factor: 10.0 # (only in Humble) + PathAlignCritic: + enabled: true + cost_power: 1 + cost_weight: 14.0 + max_path_occupancy_ratio: 0.05 + trajectory_point_step: 3 + threshold_to_consider: 0.5 + offset_from_furthest: 20 + use_path_orientations: false + PathFollowCritic: + enabled: true + cost_power: 1 + cost_weight: 5.0 + offset_from_furthest: 5 + threshold_to_consider: 1.4 + PathAngleCritic: + # increased offset_from_furthest to default value to help reduce the vehicle oscillating along the path + enabled: true + cost_power: 1 + cost_weight: 2.0 + offset_from_furthest: 20 + threshold_to_consider: 0.5 + max_angle_to_furthest: 1.0 + mode: 0 + # TwirlingCritic: + # enabled: true + # twirling_cost_power: 1 + # twirling_cost_weight: 10.0 + +local_costmap: + local_costmap: + ros__parameters: + update_frequency: 5.0 + publish_frequency: 2.0 + global_frame: odom + robot_base_frame: base_link + use_sim_time: True + rolling_window: True + width: 10 + height: 10 + resolution: 0.05 + # Can either use the robot_radius or footprint parameter + footprint: "[ [0.17, 0.33], [0.17, -0.33], [-0.74, -0.33], [-0.74, 0.33] ]" + plugins: ["voxel_layer", "inflation_layer"] + inflation_layer: + plugin: "nav2_costmap_2d::InflationLayer" + inflation_radius: 0.75 # Adjust inflation_radius to change how close robot comes to obstacles + cost_scaling_factor: 5.0 + obstacle_layer: + plugin: "nav2_costmap_2d::ObstacleLayer" + enabled: True + observation_sources: scan + scan: + topic: /scan + max_obstacle_height: 2.0 + clearing: True + marking: True + data_type: "LaserScan" + voxel_layer: + plugin: "nav2_costmap_2d::VoxelLayer" + enabled: True + publish_voxel_map: True + origin_z: 0.0 + z_resolution: 0.05 + z_voxels: 16 + max_obstacle_height: 2.0 + mark_threshold: 0 + observation_sources: scan + scan: + topic: /scan + max_obstacle_height: 2.0 + 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 + +global_costmap: + global_costmap: + ros__parameters: + update_frequency: 1.0 + publish_frequency: 1.0 + global_frame: map + robot_base_frame: base_link + use_sim_time: True + width: 20 + height: 20 + rolling_window: True + footprint: "[ [0.17, 0.33], [0.17, -0.33], [-0.74, -0.33], [-0.74, 0.33] ]" + resolution: 0.05 + track_unknown_space: true + plugins: ["static_layer", "obstacle_layer", "inflation_layer"] + obstacle_layer: + plugin: "nav2_costmap_2d::ObstacleLayer" + enabled: True + observation_sources: scan + scan: + topic: /scan + max_obstacle_height: 2.0 + clearing: True + marking: True + data_type: "LaserScan" + raytrace_max_range: 20.0 + raytrace_min_range: 0.0 + obstacle_max_range: 20.0 + obstacle_min_range: 0.0 + static_layer: + plugin: "nav2_costmap_2d::StaticLayer" + map_subscribe_transient_local: True + inflation_layer: + plugin: "nav2_costmap_2d::InflationLayer" + cost_scaling_factor: 5.0 + inflation_radius: 0.75 # Can change how much to inflate costmap around obstacles + always_send_full_costmap: True + +map_server: + ros__parameters: + use_sim_time: True + yaml_filename: "house.yaml" # Change what map to use + +map_saver: + ros__parameters: + use_sim_time: True + save_map_timeout: 5.0 + free_thresh_default: 0.25 + occupied_thresh_default: 0.65 + map_subscribe_transient_local: True + +planner_server: + ros__parameters: + expected_planner_frequency: 20.0 + use_sim_time: True + planner_plugins: ["GridBased"] + GridBased: + plugin: "nav2_navfn_planner/NavfnPlanner" + tolerance: 0.5 + use_astar: false + allow_unknown: true + +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 + +behavior_server: + ros__parameters: + costmap_topic: local_costmap/costmap_raw + footprint_topic: local_costmap/published_footprint + cycle_frequency: 10.0 + behavior_plugins: ["spin", "backup", "drive_on_heading", "wait"] + spin: + plugin: "nav2_behaviors/Spin" + backup: + plugin: "nav2_behaviors/BackUp" + drive_on_heading: + plugin: "nav2_behaviors/DriveOnHeading" + wait: + plugin: "nav2_behaviors/Wait" + global_frame: odom + robot_base_frame: base_link + transform_tolerance: 0.1 + use_sim_time: True + simulate_ahead_time: 2.0 + max_rotational_vel: 1.0 + min_rotational_vel: 0.4 + rotational_acc_lim: 3.2 + +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: "CLOSED_LOOP" + max_velocity: [1.0, 0.0, 0.8] # [x, y, theta] + min_velocity: [-1.0, 0.0, -0.8] # [x, y, theta] + max_accel: [1.0, 0.0, 1.0] + max_decel: [-1.0, 0.0, -1.0] + odom_topic: "odom" + odom_duration: 0.1 + deadband_velocity: [0.0, 0.0, 0.0] + velocity_timeout: 1.0