mirror of
https://github.com/ROBOTIS-GIT/turtlebot3_simulations.git
synced 2025-09-15 13:08:35 +08:00
111 lines
2.8 KiB
YAML
111 lines
2.8 KiB
YAML
controller_manager:
|
|
ros__parameters:
|
|
update_rate: 100 # Hz
|
|
|
|
joint_state_broadcaster:
|
|
type: joint_state_broadcaster/JointStateBroadcaster
|
|
|
|
diff_drive_controller:
|
|
type: diff_drive_controller/DiffDriveController
|
|
|
|
imu_broadcaster:
|
|
type: imu_sensor_broadcaster/IMUSensorBroadcaster
|
|
|
|
arm_controller:
|
|
type: joint_trajectory_controller/JointTrajectoryController
|
|
|
|
gripper_controller:
|
|
type: position_controllers/GripperActionController
|
|
|
|
diff_drive_controller:
|
|
ros__parameters:
|
|
left_wheel_names: ["wheel_left_joint"]
|
|
right_wheel_names: ["wheel_right_joint"]
|
|
|
|
wheel_separation: 0.287
|
|
#wheels_per_side: 1 # actually 2, but both are controlled by 1 signal
|
|
wheel_radius: 0.033
|
|
|
|
wheel_separation_multiplier: 1.0
|
|
left_wheel_radius_multiplier: 1.0
|
|
right_wheel_radius_multiplier: 1.0
|
|
|
|
publish_rate: 50.0
|
|
odom_frame_id: odom
|
|
base_frame_id: base_footprint
|
|
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: true
|
|
enable_odom_tf: true
|
|
|
|
cmd_vel_timeout: 0.5
|
|
#publish_limited_velocity: true
|
|
use_stamped_vel: false
|
|
#velocity_rolling_window_size: 10
|
|
|
|
# Preserve turning radius when limiting speed/acceleration/jerk
|
|
preserve_turning_radius: true
|
|
|
|
# Publish limited velocity
|
|
publish_cmd: true
|
|
|
|
# Publish wheel data
|
|
publish_wheel_data: true
|
|
|
|
# Velocity and acceleration limits
|
|
# Whenever a min_* is unspecified, default to -max_*
|
|
linear.x.has_velocity_limits: true
|
|
linear.x.has_acceleration_limits: true
|
|
linear.x.has_jerk_limits: false
|
|
linear.x.max_velocity: 0.26
|
|
linear.x.min_velocity: -0.26
|
|
linear.x.max_acceleration: 1.0
|
|
linear.x.max_jerk: 0.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: 1.82
|
|
angular.z.min_velocity: -1.82
|
|
angular.z.max_acceleration: 4.0
|
|
angular.z.min_acceleration: -4.0
|
|
angular.z.max_jerk: 0.0
|
|
angular.z.min_jerk: 0.0
|
|
|
|
imu_broadcaster:
|
|
ros__parameters:
|
|
frame_id: imu_link
|
|
sensor_name: imu
|
|
|
|
arm_controller:
|
|
ros__parameters:
|
|
joints:
|
|
- joint1
|
|
- joint2
|
|
- joint3
|
|
- joint4
|
|
interface_name: position
|
|
|
|
command_interfaces:
|
|
- position
|
|
|
|
state_interfaces:
|
|
- position
|
|
- velocity
|
|
|
|
state_publish_rate: 200.0 # Defaults to 50
|
|
action_monitor_rate: 20.0 # Defaults to 20
|
|
|
|
allow_partial_joints_goal: false # Defaults to false
|
|
open_loop_control: true
|
|
allow_integration_in_goal_trajectories: true
|
|
constraints:
|
|
stopped_velocity_tolerance: 0.01 # Defaults to 0.01
|
|
goal_time: 0.0 # Defaults to 0.0 (start immediately)
|
|
|
|
gripper_controller:
|
|
ros__parameters:
|
|
joint: gripper_left_joint
|