ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
You'll want to add a JointTrajectoryController to your ros_control
configuration.
Something like this should work:
pos_joint_traj_controller:
type: position_controllers/JointTrajectoryController
joints:
- jt1_joint
- jt2_joint
- jt3_joint
- jt4_joint
- jt5_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: 25
action_monitor_rate: 10
Note: the constraints
section could require some tweaking to get the values right for your robot.
In general being able to control individual joints is nice, but typically I don't really have a use-case for it.
To me a JointGroupPositionController
would make more sense, if you're not interested in executing trajectories.
2 | No.2 Revision |
You'll want to add a JointTrajectoryController to your ros_control
configuration.
Something like this should work:
pos_joint_traj_controller:
type: position_controllers/JointTrajectoryController
joints:
- jt1_joint
- jt2_joint
- jt3_joint
- jt4_joint
- jt5_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: jt1_joint: {trajectory: 0.2, goal: 0.1}
jt2_joint: {trajectory: 0.2, goal: 0.1}
jt3_joint: {trajectory: 0.2, goal: 0.1}
jt4_joint: {trajectory: 0.2, goal: 0.1}
jt5_joint: {trajectory: 0.2, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: 25
action_monitor_rate: 10
Note: the constraints
section could require some tweaking to get the values right for your robot.
In general being able to control individual joints is nice, but typically I don't really have a use-case for it.
To me a JointGroupPositionController
would make more sense, if you're not interested in executing trajectories.