[ros-users] how to use pr2_controller_manager with a different robot

John Hsu johnhsu at willowgarage.com
Wed Sep 1 00:48:39 UTC 2010


Hi Adam,
On the robot, I believe what you're missing is something similar to
the pr2_etherCAT
node <http://www.ros.org/wiki/pr2_etherCAT>.  In simulation we have a gazebo
plugin<http://www.ros.org/wiki/pr2_gazebo_plugins#gazebo_controller_manager>that
does the dirty work.
John


On Tue, Aug 31, 2010 at 5:34 PM, Adam Leeper <aleeper at stanford.edu> wrote:

> Hi all-
>
> I'm trying to get another robot we have here running in ROS.
>
> I have the launch file below to load the urdf and get the controller
> manager going. Right now I am using JTTeleop just because it's what I
> already had working on the pr2.
>
> When I launch and try to check the status of the controllers using
> pr2_controller_manager list, it hangs and if I kill it the traceback says it
> was waiting for 'pr2_controller_manager/list_controllers.' When I run the
> pr2 in gazebo, that service is advertised by gazebo itself... so obviously I
> have a problem.
>
> What is the correct procedure for interfacing my own hardware with ros? I
> know at some point I need to hook all this up to actual joint data coming in
> off my hardware. Can someone point me to an example of how that is
> published? Also, do the CartesianPoseController and JTTeleopController work
> with a generic urdf, or are they pr2-specific?
>
> Thanks,
> Adam
>
>
> <launch>
>   <!-- load the robot urdf -->
>   <param name="robot_description" command="cat $(find
> jks_robots)/robots/disney3dof.xml" />
>
>   <!-- Controller Manager -->
>   <include file="$(find pr2_controller_manager)/controller_manager.launch"
> />
>
>   <!-- Fake calibration ... necessary? -->
>   <node pkg="rostopic" type="rostopic" name="fake_joint_calibration"
> args="pub /calibrated std_msgs/Bool true" />
>
>   <!-- controller stuff -->
>
>   <rosparam ns="adam_cart">
>     type: JTTeleopController
>     root_name: base
>     tip_name: tool_frame
>     k_posture: 25.0
>     jacobian_inverse_damping: 0.01
>     pose_command_filter: 0.01
>     cart_gains:
>       trans:
>         p: 800.0
>         d: 15.0
>       rot:
>         p: 80.0
>         d: 1.2
>     joint_feedforward:
>       joint1: 0.0
>       joint2: 0.0
>       joint3: 0.0
>     joint_max_effort:
>       joint1: 10.0
>       joint2: 10.0
>       joint3: 10.0
>     vel_saturation_trans: 2.0
>     vel_saturation_rot: 4.0
>   </rosparam>
>
> <!-- Controllers that come up started -->
>   <node name="default_controllers_spawner" pkg="pr2_controller_manager"
> type="spawner" output="screen"
>         args="--wait-for=/calibrated adam_cart" />
>
> </launch>
>
>
>
> Adam Leeper
> Stanford University
> aleeper at stanford.edu
> 719.358.3804
>
>
> On Tue, Aug 31, 2010 at 3:00 PM, Adam Leeper <aleeper at stanford.edu> wrote:
>
>> Thanks Sachin, exactly what I needed. I got it working so I can move the
>> gripper around using a spacenav. It's fun :)
>>
>>
>>
>> Adam Leeper
>> Stanford University
>> aleeper at stanford.edu
>> 719.358.3804
>>
>>
>> On Tue, Aug 31, 2010 at 11:55 AM, Sachin Chitta <sachinc at willowgarage.com
>> > wrote:
>>
>>> Hey Adam,
>>>
>>> Here's a configuration file we have been using. Note though that this
>>> is still experimental so you may need to play with the values.
>>>
>>> Sachin
>>>
>>> <launch>
>>>  <node name="unspawn_arms"
>>>        pkg="pr2_controller_manager" type="unspawner"
>>>        args="l_arm_controller r_arm_controller" />
>>>
>>>  <rosparam ns="r_cart">
>>>    type: JTTeleopController
>>>    root_name: torso_lift_link
>>>    tip_name: r_gripper_tool_frame
>>>    k_posture: 25.0
>>>    jacobian_inverse_damping: 0.01
>>>    pose_command_filter: 0.01
>>>    cart_gains:
>>>      trans:
>>>        p: 800.0
>>>        d: 15.0
>>>      rot:
>>>        p: 80.0
>>>        d: 1.2
>>>    joint_feedforward:
>>>      r_shoulder_pan_joint: 3.33
>>>      r_shoulder_lift_joint: 1.16
>>>      r_upper_arm_roll_joint: 0.1
>>>      r_elbow_flex_joint: 0.25
>>>      r_forearm_roll_joint: 0.133
>>>      r_wrist_flex_joint: 0.0727
>>>      r_wrist_roll_joint: 0.0727
>>>    joint_max_effort:
>>>      r_shoulder_pan_joint: 11.88
>>>      r_shoulder_lift_joint: 11.64
>>>      r_upper_arm_roll_joint: 6.143
>>>      r_elbow_flex_joint: 6.804
>>>      r_forearm_roll_joint: 8.376
>>>      r_wrist_flex_joint: 5.568
>>>      r_wrist_roll_joint: 5.568
>>>
>>>    vel_saturation_trans: 2.0
>>>    vel_saturation_rot: 4.0
>>>  </rosparam>
>>>
>>>  <rosparam ns="l_cart">
>>>    type: JTTeleopController
>>>    root_name: torso_lift_link
>>>    tip_name: l_gripper_tool_frame
>>>    k_posture: 25.0
>>>    jacobian_inverse_damping: 0.01
>>>    pose_command_filter: 0.01
>>>    cart_gains:
>>>      trans:
>>>        p: 800.0
>>>        d: 15.0
>>>      rot:
>>>        p: 80.0
>>>        d: 1.2
>>>    joint_feedforward:
>>>      l_shoulder_pan_joint: 3.33
>>>      l_shoulder_lift_joint: 1.16
>>>      l_upper_arm_roll_joint: 0.1
>>>      l_elbow_flex_joint: 0.25
>>>      l_forearm_roll_joint: 0.133
>>>      l_wrist_flex_joint: 0.0727
>>>      l_wrist_roll_joint: 0.0727
>>>    joint_max_effort:
>>>      l_shoulder_pan_joint: 11.88
>>>      l_shoulder_lift_joint: 11.64
>>>      l_upper_arm_roll_joint: 6.143
>>>      l_elbow_flex_joint: 6.804
>>>      l_forearm_roll_joint: 8.376
>>>      l_wrist_flex_joint: 5.568
>>>      l_wrist_roll_joint: 5.568
>>>    vel_saturation_trans: 2.0
>>>    vel_saturation_rot: 4.0
>>>  </rosparam>
>>>
>>>  <node name="spawn_cart"
>>>        pkg="pr2_controller_manager" type="spawner"
>>>        args="l_cart r_cart" />
>>> </launch>
>>>
>>>
>>> On Tue, Aug 31, 2010 at 11:46 AM, Adam Leeper <aleeper at stanford.edu>
>>> wrote:
>>> > Hi-
>>> >
>>> > I'm sending this out as a separate request. Is there a default .yaml
>>> file
>>> > for the cartesian pose controller? I made my own but I totally guessed
>>> on
>>> > the pid gains for fb_trans and fb_rot, and I'm not sure if I'm missing
>>> > anything else. The controller manager loaded it so maybe it's ok...
>>> >
>>> > I've looked around a lot for information on using Cartesian pose
>>> controller,
>>> > the JTTeleop stuff, or related controllers, and I can't seem to find
>>> > adequate documentation on the wiki nor any configuration files in the
>>> > package directories. Should i be looking somewhere else?
>>> >
>>> > Thanks,
>>> > Adam
>>> >
>>> >
>>> > Adam Leeper
>>> > Stanford University
>>> > aleeper at stanford.edu
>>> > 719.358.3804
>>> >
>>> > _______________________________________________
>>> > ros-users mailing list
>>> > ros-users at code.ros.org
>>> > https://code.ros.org/mailman/listinfo/ros-users
>>> >
>>> >
>>>
>>>
>>>
>>> --
>>> Sachin Chitta
>>> Research Scientist
>>> Willow Garage
>>> _______________________________________________
>>> ros-users mailing list
>>> ros-users at code.ros.org
>>> https://code.ros.org/mailman/listinfo/ros-users
>>>
>>
>>
>
> _______________________________________________
> ros-users mailing list
> ros-users at code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users
>
>
-------------- next part --------------
An HTML attachment was scrubbed...
URL: /discuss/ros-users/attachments/20100831/4dfa2850/attachment.htm 


More information about the ros-users mailing list