This commit is contained in:
Björn Ellensohn 2023-10-09 16:23:05 +02:00
parent 90ddabd951
commit 0a6dd6f402
2 changed files with 4 additions and 4 deletions

View File

@ -5,7 +5,7 @@ ekf_filter_node:
# computation until it receives at least one message from one of theinputs. It will then run continuously at the # computation until it receives at least one message from one of theinputs. It will then run continuously at the
# frequency specified here, regardless of whether it receives more measurements. Defaults to 30 if unspecified. # frequency specified here, regardless of whether it receives more measurements. Defaults to 30 if unspecified.
# frequency: 30.0 # frequency: 30.0
frequency: 30.0 frequency: 50.0
# ekf_localization_node and ukf_localization_node both use a 3D omnidirectional motion model. If this parameter is # ekf_localization_node and ukf_localization_node both use a 3D omnidirectional motion model. If this parameter is
# set to true, no 3D information will be used in your state estimate. Use this if you are operating in a planar # set to true, no 3D information will be used in your state estimate. Use this if you are operating in a planar

View File

@ -195,8 +195,8 @@ controller_server:
movement_time_allowance: 10.0 movement_time_allowance: 10.0
goal_checker: goal_checker:
plugin: "nav2_controller::SimpleGoalChecker" plugin: "nav2_controller::SimpleGoalChecker"
xy_goal_tolerance: 0.25 xy_goal_tolerance: 0.35 # was 0.25
yaw_goal_tolerance: 0.25 yaw_goal_tolerance: 0.35 # was 0.25
stateful: True stateful: True
FollowPath: FollowPath:
plugin: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController" plugin: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController"
@ -398,7 +398,7 @@ velocity_smoother:
use_sim_time: True use_sim_time: True
smoothing_frequency: 20.0 smoothing_frequency: 20.0
scale_velocities: False scale_velocities: False
feedback: "OPEN_LOOP" feedback: "CLOSED_LOOP" # was OPEN_LOOP
max_velocity: [0.26, 0.0, 1.0] max_velocity: [0.26, 0.0, 1.0]
min_velocity: [-0.26, 0.0, -1.0] min_velocity: [-0.26, 0.0, -1.0]
max_accel: [2.5, 0.0, 3.2] max_accel: [2.5, 0.0, 3.2]