mirror of
https://github.com/bjoernellens1/cps_rmp220_support.git
synced 2024-11-23 15:45:08 +00:00
update
This commit is contained in:
parent
4d20b326f0
commit
e8cfd10427
@ -1,5 +1,6 @@
|
|||||||
amcl:
|
amcl:
|
||||||
ros__parameters:
|
ros__parameters:
|
||||||
|
use_sim_time: True
|
||||||
alpha1: 0.2
|
alpha1: 0.2
|
||||||
alpha2: 0.2
|
alpha2: 0.2
|
||||||
alpha3: 0.2
|
alpha3: 0.2
|
||||||
@ -40,17 +41,12 @@ amcl:
|
|||||||
|
|
||||||
bt_navigator:
|
bt_navigator:
|
||||||
ros__parameters:
|
ros__parameters:
|
||||||
|
use_sim_time: True
|
||||||
global_frame: map
|
global_frame: map
|
||||||
robot_base_frame: base_link
|
robot_base_frame: base_link
|
||||||
odom_topic: /odom
|
odom_topic: /odom
|
||||||
bt_loop_duration: 10
|
bt_loop_duration: 10
|
||||||
default_server_timeout: 20
|
default_server_timeout: 20
|
||||||
action_server_result_timeout: 900.0
|
|
||||||
navigators: ["navigate_to_pose", "navigate_through_poses"]
|
|
||||||
navigate_to_pose:
|
|
||||||
plugin: "nav2_bt_navigator/NavigateToPoseNavigator"
|
|
||||||
navigate_through_poses:
|
|
||||||
plugin: "nav2_bt_navigator/NavigateThroughPosesNavigator"
|
|
||||||
# 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
|
# '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_to_pose_w_replanning_and_recovery.xml
|
||||||
# nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
|
# nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
|
||||||
@ -71,10 +67,6 @@ bt_navigator:
|
|||||||
- nav2_goal_updated_condition_bt_node
|
- nav2_goal_updated_condition_bt_node
|
||||||
- nav2_globally_updated_goal_condition_bt_node
|
- nav2_globally_updated_goal_condition_bt_node
|
||||||
- nav2_is_path_valid_condition_bt_node
|
- nav2_is_path_valid_condition_bt_node
|
||||||
- nav2_are_error_codes_active_condition_bt_node
|
|
||||||
- nav2_would_a_controller_recovery_help_condition_bt_node
|
|
||||||
- nav2_would_a_planner_recovery_help_condition_bt_node
|
|
||||||
- nav2_would_a_smoother_recovery_help_condition_bt_node
|
|
||||||
- nav2_initial_pose_received_condition_bt_node
|
- nav2_initial_pose_received_condition_bt_node
|
||||||
- nav2_reinitialize_global_localization_service_bt_node
|
- nav2_reinitialize_global_localization_service_bt_node
|
||||||
- nav2_rate_controller_bt_node
|
- nav2_rate_controller_bt_node
|
||||||
@ -107,18 +99,24 @@ bt_navigator:
|
|||||||
- nav2_assisted_teleop_cancel_bt_node
|
- nav2_assisted_teleop_cancel_bt_node
|
||||||
- nav2_drive_on_heading_cancel_bt_node
|
- nav2_drive_on_heading_cancel_bt_node
|
||||||
- nav2_is_battery_charging_condition_bt_node
|
- nav2_is_battery_charging_condition_bt_node
|
||||||
error_code_names:
|
|
||||||
- compute_path_error_code
|
bt_navigator_navigate_through_poses_rclcpp_node:
|
||||||
- follow_path_error_code
|
ros__parameters:
|
||||||
|
use_sim_time: True
|
||||||
|
|
||||||
|
bt_navigator_navigate_to_pose_rclcpp_node:
|
||||||
|
ros__parameters:
|
||||||
|
use_sim_time: True
|
||||||
|
|
||||||
controller_server:
|
controller_server:
|
||||||
ros__parameters:
|
ros__parameters:
|
||||||
|
use_sim_time: True
|
||||||
controller_frequency: 20.0
|
controller_frequency: 20.0
|
||||||
min_x_velocity_threshold: 0.001
|
min_x_velocity_threshold: 0.001
|
||||||
min_y_velocity_threshold: 0.5
|
min_y_velocity_threshold: 0.5
|
||||||
min_theta_velocity_threshold: 0.001
|
min_theta_velocity_threshold: 0.001
|
||||||
failure_tolerance: 0.3
|
failure_tolerance: 0.3
|
||||||
progress_checker_plugins: ["progress_checker"]
|
progress_checker_plugin: "progress_checker"
|
||||||
goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker"
|
goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker"
|
||||||
controller_plugins: ["FollowPath"]
|
controller_plugins: ["FollowPath"]
|
||||||
|
|
||||||
@ -188,12 +186,12 @@ local_costmap:
|
|||||||
publish_frequency: 2.0
|
publish_frequency: 2.0
|
||||||
global_frame: odom
|
global_frame: odom
|
||||||
robot_base_frame: base_link
|
robot_base_frame: base_link
|
||||||
|
use_sim_time: True
|
||||||
rolling_window: true
|
rolling_window: true
|
||||||
width: 3
|
width: 3
|
||||||
height: 3
|
height: 3
|
||||||
resolution: 0.05
|
resolution: 0.05
|
||||||
#robot_radius: 0.22
|
robot_radius: 0.22
|
||||||
footprint: "[ [0.18, 0.255], [0.18, -0.255], [-0.54, -0.165], [-0.54, 0.165] ]"
|
|
||||||
plugins: ["voxel_layer", "inflation_layer"]
|
plugins: ["voxel_layer", "inflation_layer"]
|
||||||
inflation_layer:
|
inflation_layer:
|
||||||
plugin: "nav2_costmap_2d::InflationLayer"
|
plugin: "nav2_costmap_2d::InflationLayer"
|
||||||
@ -231,8 +229,8 @@ global_costmap:
|
|||||||
publish_frequency: 1.0
|
publish_frequency: 1.0
|
||||||
global_frame: map
|
global_frame: map
|
||||||
robot_base_frame: base_link
|
robot_base_frame: base_link
|
||||||
#robot_radius: 0.22
|
use_sim_time: True
|
||||||
footprint: "[ [0.18, 0.255], [0.18, -0.255], [-0.54, -0.165], [-0.54, 0.165] ]"
|
robot_radius: 0.22
|
||||||
resolution: 0.05
|
resolution: 0.05
|
||||||
track_unknown_space: true
|
track_unknown_space: true
|
||||||
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
|
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
|
||||||
@ -259,15 +257,16 @@ global_costmap:
|
|||||||
inflation_radius: 0.55
|
inflation_radius: 0.55
|
||||||
always_send_full_costmap: True
|
always_send_full_costmap: True
|
||||||
|
|
||||||
# The yaml_filename does not need to be specified since it going to be set by defaults in launch.
|
map_server:
|
||||||
# If you'd rather set it in the yaml, remove the default "map" value in the tb3_simulation_launch.py
|
ros__parameters:
|
||||||
# file & provide full path to map below. If CLI map configuration or launch default is provided, that will be used.
|
use_sim_time: True
|
||||||
# map_server:
|
# Overridden in launch by the "map" launch configuration or provided default value.
|
||||||
# ros__parameters:
|
# To use in yaml, remove the default "map" value in the tb3_simulation_launch.py file & provide full path to map below.
|
||||||
# yaml_filename: ""
|
yaml_filename: ""
|
||||||
|
|
||||||
map_saver:
|
map_saver:
|
||||||
ros__parameters:
|
ros__parameters:
|
||||||
|
use_sim_time: True
|
||||||
save_map_timeout: 5.0
|
save_map_timeout: 5.0
|
||||||
free_thresh_default: 0.25
|
free_thresh_default: 0.25
|
||||||
occupied_thresh_default: 0.65
|
occupied_thresh_default: 0.65
|
||||||
@ -276,6 +275,7 @@ map_saver:
|
|||||||
planner_server:
|
planner_server:
|
||||||
ros__parameters:
|
ros__parameters:
|
||||||
expected_planner_frequency: 20.0
|
expected_planner_frequency: 20.0
|
||||||
|
use_sim_time: True
|
||||||
planner_plugins: ["GridBased"]
|
planner_plugins: ["GridBased"]
|
||||||
GridBased:
|
GridBased:
|
||||||
plugin: "nav2_navfn_planner/NavfnPlanner"
|
plugin: "nav2_navfn_planner/NavfnPlanner"
|
||||||
@ -285,6 +285,7 @@ planner_server:
|
|||||||
|
|
||||||
smoother_server:
|
smoother_server:
|
||||||
ros__parameters:
|
ros__parameters:
|
||||||
|
use_sim_time: True
|
||||||
smoother_plugins: ["simple_smoother"]
|
smoother_plugins: ["simple_smoother"]
|
||||||
simple_smoother:
|
simple_smoother:
|
||||||
plugin: "nav2_smoother::SimpleSmoother"
|
plugin: "nav2_smoother::SimpleSmoother"
|
||||||
@ -294,10 +295,8 @@ smoother_server:
|
|||||||
|
|
||||||
behavior_server:
|
behavior_server:
|
||||||
ros__parameters:
|
ros__parameters:
|
||||||
local_costmap_topic: local_costmap/costmap_raw
|
costmap_topic: local_costmap/costmap_raw
|
||||||
global_costmap_topic: global_costmap/costmap_raw
|
footprint_topic: local_costmap/published_footprint
|
||||||
local_footprint_topic: local_costmap/published_footprint
|
|
||||||
global_footprint_topic: global_costmap/published_footprint
|
|
||||||
cycle_frequency: 10.0
|
cycle_frequency: 10.0
|
||||||
behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"]
|
behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"]
|
||||||
spin:
|
spin:
|
||||||
@ -310,20 +309,24 @@ behavior_server:
|
|||||||
plugin: "nav2_behaviors/Wait"
|
plugin: "nav2_behaviors/Wait"
|
||||||
assisted_teleop:
|
assisted_teleop:
|
||||||
plugin: "nav2_behaviors/AssistedTeleop"
|
plugin: "nav2_behaviors/AssistedTeleop"
|
||||||
local_frame: odom
|
global_frame: odom
|
||||||
global_frame: map
|
|
||||||
robot_base_frame: base_link
|
robot_base_frame: base_link
|
||||||
transform_tolerance: 0.1
|
transform_tolerance: 0.1
|
||||||
|
use_sim_time: true
|
||||||
simulate_ahead_time: 2.0
|
simulate_ahead_time: 2.0
|
||||||
max_rotational_vel: 1.0
|
max_rotational_vel: 1.0
|
||||||
min_rotational_vel: 0.4
|
min_rotational_vel: 0.4
|
||||||
rotational_acc_lim: 3.2
|
rotational_acc_lim: 3.2
|
||||||
|
|
||||||
|
robot_state_publisher:
|
||||||
|
ros__parameters:
|
||||||
|
use_sim_time: True
|
||||||
|
|
||||||
waypoint_follower:
|
waypoint_follower:
|
||||||
ros__parameters:
|
ros__parameters:
|
||||||
|
use_sim_time: True
|
||||||
loop_rate: 20
|
loop_rate: 20
|
||||||
stop_on_failure: false
|
stop_on_failure: false
|
||||||
action_server_result_timeout: 900.0
|
|
||||||
waypoint_task_executor_plugin: "wait_at_waypoint"
|
waypoint_task_executor_plugin: "wait_at_waypoint"
|
||||||
wait_at_waypoint:
|
wait_at_waypoint:
|
||||||
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
|
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
|
||||||
@ -332,6 +335,7 @@ waypoint_follower:
|
|||||||
|
|
||||||
velocity_smoother:
|
velocity_smoother:
|
||||||
ros__parameters:
|
ros__parameters:
|
||||||
|
use_sim_time: True
|
||||||
smoothing_frequency: 20.0
|
smoothing_frequency: 20.0
|
||||||
scale_velocities: False
|
scale_velocities: False
|
||||||
feedback: "OPEN_LOOP"
|
feedback: "OPEN_LOOP"
|
||||||
|
Loading…
Reference in New Issue
Block a user