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
c7ff5a593e
commit
88ed614af0
@ -111,9 +111,9 @@ bt_navigator_navigate_to_pose_rclcpp_node:
|
|||||||
controller_server:
|
controller_server:
|
||||||
ros__parameters:
|
ros__parameters:
|
||||||
use_sim_time: True
|
use_sim_time: True
|
||||||
controller_frequency: 20.0
|
controller_frequency: 50.0
|
||||||
min_x_velocity_threshold: 0.001
|
min_x_velocity_threshold: 0.001
|
||||||
min_y_velocity_threshold: 0.5
|
min_y_velocity_threshold: 0.001
|
||||||
min_theta_velocity_threshold: 0.001
|
min_theta_velocity_threshold: 0.001
|
||||||
failure_tolerance: 0.3
|
failure_tolerance: 0.3
|
||||||
progress_checker_plugin: "progress_checker"
|
progress_checker_plugin: "progress_checker"
|
||||||
@ -156,18 +156,18 @@ controller_server:
|
|||||||
min_vel_x: 0.0
|
min_vel_x: 0.0
|
||||||
min_vel_y: 0.0
|
min_vel_y: 0.0
|
||||||
max_vel_x: 0.26
|
max_vel_x: 0.26
|
||||||
max_vel_y: 0.0
|
max_vel_y: 0.26
|
||||||
max_vel_theta: 1.0
|
max_vel_theta: 1.0
|
||||||
min_speed_xy: 0.001
|
min_speed_xy: 0.001
|
||||||
max_speed_xy: 0.26
|
max_speed_xy: 0.26
|
||||||
min_speed_theta: 0.0
|
min_speed_theta: 0.0
|
||||||
# Add high threshold velocity for turtlebot 3 issue.
|
# Add high threshold velocity for turtlebot 3 issue.
|
||||||
# https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75
|
# https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75
|
||||||
acc_lim_x: 0.05 # was 2.5
|
acc_lim_x: 0.02 # was 2.5
|
||||||
acc_lim_y: 0.1
|
acc_lim_y: 0.02
|
||||||
acc_lim_theta: 1.0 # was 3.2
|
acc_lim_theta: 1.0 # was 3.2
|
||||||
decel_lim_x: -0.05 # was -2.5
|
decel_lim_x: -0.02 # was -2.5
|
||||||
decel_lim_y: 0.0
|
decel_lim_y: -0.02
|
||||||
decel_lim_theta: -0.1 # was -3.2
|
decel_lim_theta: -0.1 # was -3.2
|
||||||
vx_samples: 20
|
vx_samples: 20
|
||||||
vy_samples: 5
|
vy_samples: 5
|
||||||
@ -195,7 +195,7 @@ controller_server:
|
|||||||
local_costmap:
|
local_costmap:
|
||||||
local_costmap:
|
local_costmap:
|
||||||
ros__parameters:
|
ros__parameters:
|
||||||
update_frequency: 10.0 # was 5.0
|
update_frequency: 20.0 # was 5.0
|
||||||
publish_frequency: 5.0 # was 2.0
|
publish_frequency: 5.0 # was 2.0
|
||||||
global_frame: odom
|
global_frame: odom
|
||||||
robot_base_frame: base_link
|
robot_base_frame: base_link
|
||||||
|
Loading…
Reference in New Issue
Block a user