cyphal_hardware_interface/bringup/config/staubi_controllers.yaml
2025-07-19 15:26:29 +02:00

66 lines
1.9 KiB
YAML

controller_manager:
ros__parameters:
update_rate: 60 # Hz
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
staubi_base_controller:
type: diff_drive_controller/DiffDriveController
staubi_base_controller:
ros__parameters:
left_wheel_names: ["left_wheel_joint"]
right_wheel_names: ["right_wheel_joint"]
use_stamped_vel: false
wheel_separation: 0.222
#wheels_per_side: 1 # actually 2, but both are controlled by 1 signal
wheel_radius: 0.0355
wheel_separation_multiplier: 1.0
left_wheel_radius_multiplier: 1.0
right_wheel_radius_multiplier: 1.0
publish_rate: 60.0
odom_frame_id: odom
base_frame_id: base_link
pose_covariance_diagonal : [0.001, 0.001, 0.001, 0.001, 0.001, 0.01]
twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.01]
open_loop: false
# open_loop: true
position_feedback: true
enable_odom_tf: true
cmd_vel_timeout: 0.5
#publish_limited_velocity: true
#velocity_rolling_window_size: 10
# Velocity and acceleration limits
# Whenever a min_* is unspecified, default to -max_*
linear.x.has_velocity_limits: true
# linear.x.has_velocity_limits: false
linear.x.has_acceleration_limits: true
# linear.x.has_acceleration_limits: false
# linear.x.has_jerk_limits: true
linear.x.has_jerk_limits: false
linear.x.max_velocity: 1.3
linear.x.min_velocity: -0.3
# linear.x.max_acceleration: 10.0
linear.x.max_acceleration: 1.4
# linear.x.max_acceleration: 10.0
# linear.x.max_jerk: 1.0
# linear.x.min_jerk: 0.0
angular.z.has_velocity_limits: true
angular.z.has_acceleration_limits: true
angular.z.has_jerk_limits: false
angular.z.max_velocity: 7.0
angular.z.min_velocity: -7.0
angular.z.max_acceleration: 3.0
angular.z.min_acceleration: -3.0
angular.z.max_jerk: 0.0
angular.z.min_jerk: 0.0