mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 01:50:46 +02:00
53 lines
1.6 KiB
YAML
53 lines
1.6 KiB
YAML
# Settings for ros_control control loop
|
|
hardware_control_loop:
|
|
loop_hz: 125
|
|
|
|
# Settings for ros_control hardware interface
|
|
hardware_interface:
|
|
joints:
|
|
- shoulder_pan_joint
|
|
- shoulder_lift_joint
|
|
- elbow_joint
|
|
- wrist_1_joint
|
|
- wrist_2_joint
|
|
- wrist_3_joint
|
|
|
|
# Publish all joint states ----------------------------------
|
|
joint_state_controller:
|
|
type: joint_state_controller/JointStateController
|
|
publish_rate: 125
|
|
|
|
# Publish wrench ----------------------------------
|
|
force_torque_sensor_controller:
|
|
type: force_torque_sensor_controller/ForceTorqueSensorController
|
|
publish_rate: 125
|
|
|
|
# Publish speed_scaling factor
|
|
speed_scaling_state_controller:
|
|
type: ur_controllers/SpeedScalingStateController
|
|
publish_rate: 125
|
|
|
|
# Joint Trajectory Controller - position based -------------------------------
|
|
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
|
|
pos_based_pos_traj_controller:
|
|
type: position_controllers/ScaledJointTrajectoryController
|
|
joints:
|
|
- shoulder_pan_joint
|
|
- shoulder_lift_joint
|
|
- elbow_joint
|
|
- wrist_1_joint
|
|
- wrist_2_joint
|
|
- wrist_3_joint
|
|
constraints:
|
|
goal_time: 0.6
|
|
stopped_velocity_tolerance: 0.05
|
|
shoulder_pan_joint: {trajectory: 0.2, goal: 0.1}
|
|
shoulder_lift_joint: {trajectory: 0.2, goal: 0.1}
|
|
elbow_joint: {trajectory: 0.2, goal: 0.1}
|
|
wrist_1_joint: {trajectory: 0.2, goal: 0.1}
|
|
wrist_2_joint: {trajectory: 0.2, goal: 0.1}
|
|
wrist_3_joint: {trajectory: 0.2, goal: 0.1}
|
|
stop_trajectory_duration: 0.5
|
|
state_publish_rate: 500
|
|
action_monitor_rate: 10
|