改速度参数
This commit is contained in:
parent
86f0c06c31
commit
528a2dfa11
2
nav.sh
2
nav.sh
@ -1,7 +1,7 @@
|
||||
source install/setup.bash
|
||||
|
||||
commands=(
|
||||
"ros2 launch rm_serial_driver rm_serial_driver.launch.py"
|
||||
# "ros2 launch rm_serial_driver rm_serial_driver.launch.py"
|
||||
"ros2 launch rm_decision decision.launch.py"
|
||||
"ros2 launch rm_simpal_move simple_move.launch.py"
|
||||
"ros2 launch rm_nav_bringup bringup_real.launch.py \
|
||||
|
||||
@ -106,7 +106,7 @@ controller_server:
|
||||
general_goal_checker:
|
||||
stateful: True
|
||||
plugin: "nav2_controller::SimpleGoalChecker"
|
||||
xy_goal_tolerance: 0.25
|
||||
xy_goal_tolerance: 0.4
|
||||
yaw_goal_tolerance: 6.28
|
||||
FollowPath:
|
||||
plugin: teb_local_planner::TebLocalPlannerROS
|
||||
@ -116,7 +116,7 @@ controller_server:
|
||||
# Trajectory
|
||||
#*******************************************************************************
|
||||
teb_autosize: 1.0 #是否自动调整轨迹大小。根据时间分辨率自动调整轨迹大小
|
||||
dt_ref: 0.6 #轨迹的期望时间分辨率(应该与底层控制速率的数量级相符)
|
||||
dt_ref: 0.3 #轨迹的期望时间分辨率(应该与底层控制速率的数量级相符)
|
||||
dt_hysteresis: 0.06 #自动调整大小的滞后(根据当前时间分辨率 dt):通常为 dt_ref 的 10%
|
||||
max_samples: 500 #最大样本数量;警告:如果太小,离散化/分辨率可能不足以用于给定的机器人模型,或者避障不再有效。
|
||||
global_plan_overwrite_orientation: False #覆盖全局规划器提供的局部子目标的方向
|
||||
@ -139,10 +139,9 @@ controller_server:
|
||||
#*******************************************************************************
|
||||
# Robot
|
||||
#*******************************************************************************
|
||||
max_vel_x: 2.0 #最大平移速度
|
||||
max_vel_x_backwards: 2.0 #最大后退速度
|
||||
max_vel_theta: 0.0 #最大转向角速度(暂时关闭wz)
|
||||
acc_lim_x: 2.0 #最大平移加速度
|
||||
max_vel_x: 1.2 #最大平移速度
|
||||
max_vel_x_backwards: 1.2 #最大后退 max_vel_theta: 0.0 #最大转向角速度(暂时关闭wz)
|
||||
acc_lim_x: 1.2 #最大平移加速度
|
||||
acc_lim_theta: 0.0 #最大角加速度(暂时关闭wz)
|
||||
is_footprint_dynamic: False #如果为真,在检查轨迹可行性之前更新足迹
|
||||
use_proportional_saturation: False #如果为true,则按比例减少所有扭曲分量(线性x和y以及角度z)(如果任何扭曲分量超过其相应的界限),而不是单独饱和每个扭曲分量
|
||||
@ -158,8 +157,8 @@ controller_server:
|
||||
#*******************************************************************************
|
||||
# Robot/Omni 此部分参数仅适用于全方位移动机器人
|
||||
#*******************************************************************************
|
||||
max_vel_y: 2.0
|
||||
acc_lim_y: 2.0
|
||||
max_vel_y: 1.2
|
||||
acc_lim_y: 1.2
|
||||
|
||||
#*******************************************************************************
|
||||
# GoalTolerance 目标容差
|
||||
@ -401,11 +400,11 @@ velocity_smoother:
|
||||
smoothing_frequency: 20.0
|
||||
scale_velocities: False
|
||||
feedback: "OPEN_LOOP"
|
||||
max_velocity: [2.0, 2.0, 0.0]
|
||||
min_velocity: [-2.0, -2.0, 0.0]
|
||||
max_velocity: [1.2, 1.2, 0.0]
|
||||
min_velocity: [-1.2, -1.2, 0.0]
|
||||
deadband_velocity: [0.0, 0.0, 0.0]
|
||||
velocity_timeout: 1.0
|
||||
max_accel: [2.0, 2.0, 0.0]
|
||||
max_decel: [-2.0, -2.0, 0.0]
|
||||
max_accel: [1.2, 1.2, 0.0]
|
||||
max_decel: [-1.2, -1.2, 0.0]
|
||||
odom_topic: "Odometry"
|
||||
odom_duration: 0.1
|
||||
@ -124,7 +124,7 @@ python3 move_test_new.py
|
||||
**PID 模式:**
|
||||
```bash
|
||||
ros2 topic pub /nav_goal rm_msgs/msg/NavGoal "{
|
||||
control_mode: 0,
|
||||
control_mode: 1,
|
||||
x: 1.0,
|
||||
y: -5.0,
|
||||
angle: 0.0,
|
||||
|
||||
Loading…
Reference in New Issue
Block a user