turtlebot3_simulations/turtlebot3_manipulation_gazebo/config/gazebo_controller_manager.yaml

55 lines
1.2 KiB
YAML

controller_manager:
ros__parameters:
use_sim_time: True
update_rate: 1000 # Hz
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
imu_broadcaster:
type: imu_sensor_broadcaster/IMUSensorBroadcaster
arm_controller:
type: joint_trajectory_controller/JointTrajectoryController
gripper_controller:
type: position_controllers/GripperActionController
imu_broadcaster:
ros__parameters:
use_sim_time: True
frame_id: imu_link
sensor_name: imu
arm_controller:
ros__parameters:
use_sim_time: True
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:
use_sim_time: True
joint: gripper_left_joint