]> defiant.homedns.org Git - ros_wild_thumper.git/blob - config/control.yaml
fix angle velocity
[ros_wild_thumper.git] / config / control.yaml
1 joint_state_controller:
2   type: "joint_state_controller/JointStateController"
3   publish_rate: 20
4
5 diff_drive_controller:
6   type: "diff_drive_controller/DiffDriveController"
7   left_wheel: ['front_left_wheel_joint', 'rear_left_wheel_joint']
8   right_wheel: ['front_right_wheel_joint', 'rear_right_wheel_joint']
9   publish_rate: 20
10   pose_covariance_diagonal:  [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 0.03]
11   twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 0.03]
12   cmd_vel_timeout: 1000000000
13
14   # Base frame_id
15   base_frame_id: base_footprint
16
17   # Odometry fused with IMU is published by robot_localization, so
18   # no need to publish a TF based on encoders alone.
19   enable_odom_tf: false
20
21   # Hardware provides wheel velocities
22   estimate_velocity_from_position: false
23
24   # Wheel separation and radius multipliers
25   wheel_separation_multiplier: 1.4126 # default: 1.0
26   wheel_radius_multiplier    : 1.0 # default: 1.0
27
28   # Velocity and acceleration limits
29   # Whenever a min_* is unspecified, default to -max_*
30   linear:
31     x:
32       has_velocity_limits    : true
33       max_velocity           : 1.5   # m/s
34       has_acceleration_limits: true
35       max_acceleration       : 2.0   # m/s^2
36   angular:
37     z:
38       has_velocity_limits    : true
39       max_velocity           : 3.0   # rad/s
40       has_acceleration_limits: true
41       max_acceleration       : 3.0   # rad/s^2