ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

I did find a solution. It looks like MoveIt! and ros_control need separate yaml files. I called the MoveIt! file moveit_controllers.yaml:

controller_list:
  - name: left_vel_based_pos_traj_controller
    action_ns: follow_joint_trajectory
    type: FollowJointTrajectory
    joints:
      - left_ur5_shoulder_pan_joint
      - left_ur5_shoulder_lift_joint
      - left_ur5_elbow_joint
      - left_ur5_wrist_1_joint
      - left_ur5_wrist_2_joint
      - left_ur5_wrist_3_joint

The yaml for ros_control. I called it ros_control_controllers.yaml:

# These controllers should match with what MoveIt! expects (moveit_controllers.yaml).
# Settings for ros_control control loop
hardware_control_loop:
   loop_hz: 125

# Settings for ros_control hardware interface
hardware_interface:
   joints:
     - left_ur5_shoulder_pan_joint
     - left_ur5_shoulder_lift_joint
     - left_ur5_elbow_joint
     - left_ur5_wrist_1_joint
     - left_ur5_wrist_2_joint
     - left_ur5_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

# Left trajectories
left_vel_based_pos_traj_controller:
  action_ns: left_ur5_follow_joint_trajectory
  type: velocity_controllers/JointTrajectoryController
  joints:
    - left_ur5_shoulder_pan_joint
    - left_ur5_shoulder_lift_joint
    - left_ur5_elbow_joint
    - left_ur5_wrist_1_joint
    - left_ur5_wrist_2_joint
    - left_ur5_wrist_3_joint
  constraints:
    goal_time: 0.6
    stopped_velocity_tolerance: 0.05
    shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
    shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
    elbow_joint: {trajectory: 0.1, goal: 0.1}
    wrist_1_joint: {trajectory: 0.1, goal: 0.1}
    wrist_2_joint: {trajectory: 0.1, goal: 0.1}
    wrist_3_joint: {trajectory: 0.1, goal: 0.1}
  stop_trajectory_duration: 0.5
  state_publish_rate:  125
  action_monitor_rate: 10
  gains:
    #!!These values are useable, but maybe not optimal
    left_ur5_shoulder_pan_joint: {p: 1.2,  i: 0.0, d: 0.1, i_clamp: 1}
    left_ur5_shoulder_lift_joint: {p: 1.2,  i: 0.0, d: 0.1, i_clamp: 1}
    left_ur5_elbow_joint: {p: 1.2,  i: 0.0, d: 0.1, i_clamp: 1}
    left_ur5_wrist_1_joint: {p: 1.2,  i: 0.0, d: 0.1, i_clamp: 1}
    left_ur5_wrist_2_joint: {p: 1.2,  i: 0.0, d: 0.1, i_clamp: 1}
    left_ur5_wrist_3_joint: {p: 1.2,  i: 0.0, d: 0.1, i_clamp: 1}

I did find a solution. It looks like MoveIt! and ros_control need separate yaml files. I called the MoveIt! file moveit_controllers.yaml:

controller_list:
  - name: left_vel_based_pos_traj_controller
    action_ns: follow_joint_trajectory
    type: FollowJointTrajectory
    joints:
      - left_ur5_shoulder_pan_joint
      - left_ur5_shoulder_lift_joint
      - left_ur5_elbow_joint
      - left_ur5_wrist_1_joint
      - left_ur5_wrist_2_joint
      - left_ur5_wrist_3_joint

The yaml for ros_control. I called it ros_control_controllers.yaml:

# These controllers should match with what MoveIt! expects (moveit_controllers.yaml).
# Settings for ros_control control loop
hardware_control_loop:
   loop_hz: 125

# Settings for ros_control hardware interface
hardware_interface:
   joints:
     - left_ur5_shoulder_pan_joint
     - left_ur5_shoulder_lift_joint
     - left_ur5_elbow_joint
     - left_ur5_wrist_1_joint
     - left_ur5_wrist_2_joint
     - left_ur5_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

# Left trajectories
left_vel_based_pos_traj_controller:
  action_ns: left_ur5_follow_joint_trajectory
  type: velocity_controllers/JointTrajectoryController
  joints:
    - left_ur5_shoulder_pan_joint
    - left_ur5_shoulder_lift_joint
    - left_ur5_elbow_joint
    - left_ur5_wrist_1_joint
    - left_ur5_wrist_2_joint
    - left_ur5_wrist_3_joint
  constraints:
    goal_time: 0.6
    stopped_velocity_tolerance: 0.05
    shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
    shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
    elbow_joint: {trajectory: 0.1, goal: 0.1}
    wrist_1_joint: {trajectory: 0.1, goal: 0.1}
    wrist_2_joint: {trajectory: 0.1, goal: 0.1}
    wrist_3_joint: {trajectory: 0.1, goal: 0.1}
  stop_trajectory_duration: 0.5
  state_publish_rate:  125
  action_monitor_rate: 10
  gains:
    #!!These values are useable, but maybe not optimal
    left_ur5_shoulder_pan_joint: {p: 1.2,  i: 0.0, d: 0.1, i_clamp: 1}
    left_ur5_shoulder_lift_joint: {p: 1.2,  i: 0.0, d: 0.1, i_clamp: 1}
    left_ur5_elbow_joint: {p: 1.2,  i: 0.0, d: 0.1, i_clamp: 1}
    left_ur5_wrist_1_joint: {p: 1.2,  i: 0.0, d: 0.1, i_clamp: 1}
    left_ur5_wrist_2_joint: {p: 1.2,  i: 0.0, d: 0.1, i_clamp: 1}
    left_ur5_wrist_3_joint: {p: 1.2,  i: 0.0, d: 0.1, i_clamp: 1}

It looks like MoveIt! and ros_control need separate yaml files. I called named the MoveIt! file moveit_controllers.yaml:

controller_list:
  - name: left_vel_based_pos_traj_controller
    action_ns: follow_joint_trajectory
    type: FollowJointTrajectory
    joints:
      - left_ur5_shoulder_pan_joint
      - left_ur5_shoulder_lift_joint
      - left_ur5_elbow_joint
      - left_ur5_wrist_1_joint
      - left_ur5_wrist_2_joint
      - left_ur5_wrist_3_joint

The yaml for ros_control. I called named it ros_control_controllers.yaml:

# These controllers should match with what MoveIt! expects (moveit_controllers.yaml).
# Settings for ros_control control loop
hardware_control_loop:
   loop_hz: 125

# Settings for ros_control hardware interface
hardware_interface:
   joints:
     - left_ur5_shoulder_pan_joint
     - left_ur5_shoulder_lift_joint
     - left_ur5_elbow_joint
     - left_ur5_wrist_1_joint
     - left_ur5_wrist_2_joint
     - left_ur5_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

# Left trajectories
left_vel_based_pos_traj_controller:
  action_ns: left_ur5_follow_joint_trajectory
  type: velocity_controllers/JointTrajectoryController
  joints:
    - left_ur5_shoulder_pan_joint
    - left_ur5_shoulder_lift_joint
    - left_ur5_elbow_joint
    - left_ur5_wrist_1_joint
    - left_ur5_wrist_2_joint
    - left_ur5_wrist_3_joint
  constraints:
    goal_time: 0.6
    stopped_velocity_tolerance: 0.05
    shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
    shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
    elbow_joint: {trajectory: 0.1, goal: 0.1}
    wrist_1_joint: {trajectory: 0.1, goal: 0.1}
    wrist_2_joint: {trajectory: 0.1, goal: 0.1}
    wrist_3_joint: {trajectory: 0.1, goal: 0.1}
  stop_trajectory_duration: 0.5
  state_publish_rate:  125
  action_monitor_rate: 10
  gains:
    #!!These values are useable, but maybe not optimal
    left_ur5_shoulder_pan_joint: {p: 1.2,  i: 0.0, d: 0.1, i_clamp: 1}
    left_ur5_shoulder_lift_joint: {p: 1.2,  i: 0.0, d: 0.1, i_clamp: 1}
    left_ur5_elbow_joint: {p: 1.2,  i: 0.0, d: 0.1, i_clamp: 1}
    left_ur5_wrist_1_joint: {p: 1.2,  i: 0.0, d: 0.1, i_clamp: 1}
    left_ur5_wrist_2_joint: {p: 1.2,  i: 0.0, d: 0.1, i_clamp: 1}
    left_ur5_wrist_3_joint: {p: 1.2,  i: 0.0, d: 0.1, i_clamp: 1}