add apm
This commit is contained in:
@@ -0,0 +1,4 @@
|
||||
# Publish all joint states -----------------------------------
|
||||
joint_state_controller:
|
||||
type: joint_state_controller/JointStateController
|
||||
publish_rate: 50
|
||||
55
Controllers/Packages/cititruck_description/config/steerdrive_controller.yaml
Executable file
55
Controllers/Packages/cititruck_description/config/steerdrive_controller.yaml
Executable file
@@ -0,0 +1,55 @@
|
||||
# -----------------------------------
|
||||
mobile_base_controller:
|
||||
type : "steer_drive_controller/SteerDriveController"
|
||||
rear_wheel: '$(arg prefix)steer2sd_wheel_joint'
|
||||
front_steer: '$(arg prefix)base2steer_joint'
|
||||
publish_rate: 41.2 # this is what the real MiR platform publishes (default: 50)
|
||||
# These covariances are exactly what the real MiR platform publishes
|
||||
pose_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]
|
||||
twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]
|
||||
enable_odom_tf: false
|
||||
|
||||
# Wheel separation and diameter. These are both optional.
|
||||
# diff_drive_controller will attempt to read either one or both from the
|
||||
# URDF if not specified as a parameter.
|
||||
# We don't set the value here because it's different for each MiR type (100, 250, ...), and
|
||||
# the plugin figures out the correct values.
|
||||
wheel_separation : 1.3268
|
||||
wheel_radius : 0.125
|
||||
|
||||
# Wheel separation and radius multipliers
|
||||
wheel_separation_multiplier: 1.0 # default: 1.0
|
||||
wheel_radius_multiplier : 1.0 # default: 1.0
|
||||
|
||||
# Steer position angle multipliers for fine tuning.
|
||||
steer_pos_multiplier : 1.0
|
||||
|
||||
# Velocity commands timeout [s], default 0.5
|
||||
cmd_vel_timeout: 0.25
|
||||
|
||||
# frame_ids (same as real MiR platform)
|
||||
base_frame_id: $(arg prefix)base_footprint # default: base_link
|
||||
odom_frame_id: $(arg prefix)odom # default: odom
|
||||
|
||||
# Velocity and acceleration limits
|
||||
# Whenever a min_* is unspecified, default to -max_*
|
||||
linear:
|
||||
x:
|
||||
has_velocity_limits : true
|
||||
max_velocity : 1.5 # m/s
|
||||
min_velocity : -1.5 # m/s
|
||||
has_acceleration_limits: true
|
||||
max_acceleration : 3.0 # m/s^2
|
||||
min_acceleration : -3.0 # m/s^2
|
||||
has_jerk_limits : false
|
||||
max_jerk : 5.0 # m/s^3
|
||||
angular:
|
||||
z:
|
||||
has_velocity_limits : true
|
||||
max_velocity : 2.0 # rad/s
|
||||
min_velocity : -2.0
|
||||
has_acceleration_limits: true
|
||||
max_acceleration : 1.5 # rad/s^2
|
||||
min_acceleration : -1.5
|
||||
has_jerk_limits : false
|
||||
max_jerk : 2.5 # rad/s^3
|
||||
Reference in New Issue
Block a user