Thanks Sachin, exactly what I needed. I got it working so I can move the gripper around using a spacenav. It's fun :)<br><br><br clear="all">Adam Leeper<br>Stanford University<br><a href="mailto:aleeper@stanford.edu">aleeper@stanford.edu</a><br>
719.358.3804<br>
<br><br><div class="gmail_quote">On Tue, Aug 31, 2010 at 11:55 AM, Sachin Chitta <span dir="ltr"><<a href="mailto:sachinc@willowgarage.com">sachinc@willowgarage.com</a>></span> wrote:<br><blockquote class="gmail_quote" style="margin: 0pt 0pt 0pt 0.8ex; border-left: 1px solid rgb(204, 204, 204); padding-left: 1ex;">
Hey Adam,<br>
<br>
Here's a configuration file we have been using. Note though that this<br>
is still experimental so you may need to play with the values.<br>
<br>
Sachin<br>
<br>
<launch><br>
  <node name="unspawn_arms"<br>
        pkg="pr2_controller_manager" type="unspawner"<br>
        args="l_arm_controller r_arm_controller" /><br>
<br>
  <rosparam ns="r_cart"><br>
    type: JTTeleopController<br>
    root_name: torso_lift_link<br>
    tip_name: r_gripper_tool_frame<br>
    k_posture: 25.0<br>
    jacobian_inverse_damping: 0.01<br>
    pose_command_filter: 0.01<br>
    cart_gains:<br>
      trans:<br>
        p: 800.0<br>
        d: 15.0<br>
      rot:<br>
        p: 80.0<br>
        d: 1.2<br>
    joint_feedforward:<br>
      r_shoulder_pan_joint: 3.33<br>
      r_shoulder_lift_joint: 1.16<br>
      r_upper_arm_roll_joint: 0.1<br>
      r_elbow_flex_joint: 0.25<br>
      r_forearm_roll_joint: 0.133<br>
      r_wrist_flex_joint: 0.0727<br>
      r_wrist_roll_joint: 0.0727<br>
    joint_max_effort:<br>
      r_shoulder_pan_joint: 11.88<br>
      r_shoulder_lift_joint: 11.64<br>
      r_upper_arm_roll_joint: 6.143<br>
      r_elbow_flex_joint: 6.804<br>
      r_forearm_roll_joint: 8.376<br>
      r_wrist_flex_joint: 5.568<br>
      r_wrist_roll_joint: 5.568<br>
<br>
    vel_saturation_trans: 2.0<br>
    vel_saturation_rot: 4.0<br>
  </rosparam><br>
<br>
  <rosparam ns="l_cart"><br>
    type: JTTeleopController<br>
    root_name: torso_lift_link<br>
    tip_name: l_gripper_tool_frame<br>
    k_posture: 25.0<br>
    jacobian_inverse_damping: 0.01<br>
    pose_command_filter: 0.01<br>
    cart_gains:<br>
      trans:<br>
        p: 800.0<br>
        d: 15.0<br>
      rot:<br>
        p: 80.0<br>
        d: 1.2<br>
    joint_feedforward:<br>
      l_shoulder_pan_joint: 3.33<br>
      l_shoulder_lift_joint: 1.16<br>
      l_upper_arm_roll_joint: 0.1<br>
      l_elbow_flex_joint: 0.25<br>
      l_forearm_roll_joint: 0.133<br>
      l_wrist_flex_joint: 0.0727<br>
      l_wrist_roll_joint: 0.0727<br>
    joint_max_effort:<br>
      l_shoulder_pan_joint: 11.88<br>
      l_shoulder_lift_joint: 11.64<br>
      l_upper_arm_roll_joint: 6.143<br>
      l_elbow_flex_joint: 6.804<br>
      l_forearm_roll_joint: 8.376<br>
      l_wrist_flex_joint: 5.568<br>
      l_wrist_roll_joint: 5.568<br>
    vel_saturation_trans: 2.0<br>
    vel_saturation_rot: 4.0<br>
  </rosparam><br>
<br>
  <node name="spawn_cart"<br>
        pkg="pr2_controller_manager" type="spawner"<br>
        args="l_cart r_cart" /><br>
</launch><br>
<div><div></div><div class="h5"><br>
<br>
On Tue, Aug 31, 2010 at 11:46 AM, Adam Leeper <<a href="mailto:aleeper@stanford.edu">aleeper@stanford.edu</a>> wrote:<br>
> Hi-<br>
><br>
> I'm sending this out as a separate request. Is there a default .yaml file<br>
> for the cartesian pose controller? I made my own but I totally guessed on<br>
> the pid gains for fb_trans and fb_rot, and I'm not sure if I'm missing<br>
> anything else. The controller manager loaded it so maybe it's ok...<br>
><br>
> I've looked around a lot for information on using Cartesian pose controller,<br>
> the JTTeleop stuff, or related controllers, and I can't seem to find<br>
> adequate documentation on the wiki nor any configuration files in the<br>
> package directories. Should i be looking somewhere else?<br>
><br>
> Thanks,<br>
> Adam<br>
><br>
><br>
> Adam Leeper<br>
> Stanford University<br>
> <a href="mailto:aleeper@stanford.edu">aleeper@stanford.edu</a><br>
> 719.358.3804<br>
><br>
</div></div>> _______________________________________________<br>
> ros-users mailing list<br>
> <a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>
> <a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a><br>
><br>
><br>
<font color="#888888"><br>
<br>
<br>
--<br>
Sachin Chitta<br>
Research Scientist<br>
Willow Garage<br>
_______________________________________________<br>
ros-users mailing list<br>
<a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>
<a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a><br>
</font></blockquote></div><br>