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

Revision history [back]

To expand on @Wim's answer, one example of using the pr2 controller infrastructure is here: pr2_arm_gazebo. It can easily be used on a non-PR2 arm, too. Here are the most important things you'll have to do (from pr2_arm_gazebo):

URDF file:

<gazebo>
  <controller:gazebo_ros_controller_manager name="gazebo_ros_controller_manager" plugin="libgazebo_ros_controller_manager.so">
    <alwaysOn>true</alwaysOn>
    <updateRate>1000.0</updateRate>
  </controller:gazebo_ros_controller_manager>
</gazebo>

Also, your URDF file needs transmissions for each joint, otherwise the pr2_controller_manager won't work.

Launch file:

...

<!-- Default Controllers -->
<rosparam command="load" file="$(find pr2_controller_configuration_gazebo)/pr2_arm_controllers.yaml" />

<!-- Controller Manager -->
<include file="$(find pr2_controller_manager)/controller_manager.launch" />

<!-- Controllers that come up loaded -->
<node name="default_loaded_controllers_spawner"
      pkg="pr2_controller_manager" type="spawner" output="screen"
      args="--wait-for=/calibrated r_arm_controller" />

<!-- Fake calibration -->
<node pkg="rostopic" type="rostopic" name="fake_joint_calibration"
      args="pub /calibrated std_msgs/Bool true" />

...

pr2_arm_controllers.yaml:

 r_arm_controller:
   type: "robot_mechanism_controllers/JointTrajectoryActionController"
   joints:
     - r_shoulder_pan_joint
     - r_shoulder_lift_joint
     - r_upper_arm_roll_joint
     - r_elbow_flex_joint
     - r_forearm_roll_joint
     - r_wrist_flex_joint
     - r_wrist_roll_joint
   gains:
     r_shoulder_pan_joint: {p: 2400.0, d: 18.0, i: 800.0, i_clamp: 4.0}
     r_shoulder_lift_joint: {p: 1200.0, d: 10.0, i: 700.0, i_clamp: 4.0}
     r_upper_arm_roll_joint: {p: 1000.0, d: 6.0, i: 600.0, i_clamp: 4.0}
     r_elbow_flex_joint: {p: 700.0, d: 4.0, i: 450, i_clamp: 4.0}
     r_forearm_roll_joint: {p: 300.0, d: 6.0, i: 300, i_clamp: 2.0}
     r_wrist_flex_joint: {p: 300.0, d: 4.0, i: 300, i_clamp: 2.0}
     r_wrist_roll_joint: {p: 300.0, d: 4.0, i: 300, i_clamp: 2.0}
   joint_trajectory_action_node:
     joints:
       - r_shoulder_pan_joint
       - r_shoulder_lift_joint
       - r_upper_arm_roll_joint
       - r_elbow_flex_joint
       - r_forearm_roll_joint
       - r_wrist_flex_joint
       - r_wrist_roll_joint
     constraints:
       goal_time: 0.6
       r_shoulder_pan_joint:
         goal: 0.02
       r_shoulder_lift_joint:
         goal: 0.02
       r_upper_arm_roll_joint:
         goal: 0.02
       r_elbow_flex_joint:
         goal: 0.02
       r_forearm_roll_joint:
         goal: 0.02
       r_wrist_flex_joint:
         goal: 0.02
       r_wrist_roll_joint:
         goal: 0.02

Now you'll have to send trajectories to the arm and experiment to find the right PID parameters. (Hint: they'll probably be rather in the range of 0-10 if you use a transmission mechanical reduction of 1).