Hi folks,

I just went through all the same stuff as both of you to get the arm navigation pipeline work on our custom 7DOF dynamixel based arm. I was able to use the ompl motion planning stack to generate a collision free trajectory that was successfully executed in both simulation and the the actual arm. I would say if you can reliably execute a joint trajectory on you arm it's a relatively small step to get the planning environment set up so that you can get ompl running.

Here's what I had to write to get it going:

1). arm_kinematics - your basic IK solver. Provides the following services:
  a). get_ik
  b). get_fk
  c). get_ik_solver_info
  d). get_fk_solver_info

Packages:
  PR2: pr2_arm_kinematics
  Mine: http://code.google.com/p/ua-ros-pkg/source/browse/#svn/trunk/arrg/ua_controllers/wubble_arm_kinematics

2). arm_kinematics_constraint_aware - basically a wrapper around arm_kinematics. Hooks up to planning environment and checks the initial and desired poses for collisions, also publishes some visualization markers. Adds get_constraint_aware_ik service to all those provided by arm_kinematics.

Packages:
  PR2: pr2_arm_kinematics_constraint_aware
  Mine: http://code.google.com/p/ua-ros-pkg/source/browse/#svn/trunk/arrg/ua_controllers/wubble_arm_kinematics_constraint_aware

3). joint_trajectory_action_controller - does what you think it does. If your are already does that, I think all you'd need to do is write a wrapper that creates a ROS action interface to it.

Packages:
  PR2: robot_mechansim_controllers - joint_trajectory_action_controller.cpp
  Mine: http://code.google.com/p/ua-ros-pkg/source/browse/#svn/trunk/arrg/ua_controllers/ax12_controller_core/nodes

4). After that you would need to write a bunch of yaml configuration files:
  a). parameters for motion planning
  b). parameters for collision checks and self filtering
  c). for collision map - collision sources, basically something that provides a point cloud of stuff around you, like a tilting laser.
  d). for collision map - self filter, stuff that should not be present in the cloud above.
  e). some padding parameters for planning_environment
  f). parameters for ompl_planning and ompl_search

    PR2: pr2_arm_navigation stack has all those scattered across a bunch of packages.

  You could look at my launch file, it is pretty long but it that has everything in one place:
http://code.google.com/p/ua-ros-pkg/source/browse/trunk/arrg/ua_robots/wubble_description/launch/wubble2_empty_world.launch

All the parameters that it loads are in here (w2_*.yaml):
http://code.google.com/p/ua-ros-pkg/source/browse/#svn/trunk/arrg/ua_robots/wubble_description/params

So I think you guys are pretty close to get the motion planner run on your arms, at least the motion planning part, now the grasping pipeline is whole different matter... I don't have experience with that, yet :)

Hope this helps you somewhat,
Anton

On Sun, Dec 5, 2010 at 10:59 AM, Konrad Banachowicz <konradb3@gmail.com> wrote:
Hi Martin,

I am doing quiet the same for irb6 manipulator. I have done all servo, trajectory, URDF stuff already.
Now i am working on running manipulation pipeline on it. For now it's looks like it would be hard work.
The manipulation pipeline (as far as i know) is used only on PR2 and It's quiet hard to get any answers about it on the list.
I recently get some stuff working (envirement_server, move_arm, trajectory_filter) (partially by some ugly hacks) but there is still a lot of work before I can say it works for me. 

Pozdrawiam
Konrad Banachowicz


2010/12/5 Martin Günther <martin.guenther1980@googlemail.com>

On Sun, 5 Dec 2010 17:39:30 +0100
Martin Günther <mguenthe@uos.de> wrote:

> Dear list,
>
> I am currently writing a ROS node for the Neuronics Katana 450 arm and
> would be happy about a few quick pointers about how to continue. I am
> aware of the ROS packages katana450, katana_ik_bridge and
> stair_katana; however, I would like to reuse as much ROS stuff for
> IK, arm navigation and motion planning as possible, so I decided to
> rewrite the code from scratch.
>
> So far,
> - I have created a URDF description of the arm;
> - I can read out the current joint angles and publish them as
> JointState messages;
> - I can move the arm to a desired joint angle configuration;
> - I can move the arm to a target pose in space, using the inverse
>   kinematics library supplied with the arm (although I'm also eager to
>   give the ROS IK a try).
>
> I have the feeling that I am almost done (right? come on, please!),
> but I'm a little overwhelmed by the wealth of arm navigation stuff in
> ROS. What are the messages/services/actions that I should provide to
> be able to interface my arm to a motion planner, and to use the ROS
> IK, and so on?
>
> Best,
> Martin

Forgot to mention: The robot arm has realtime controllers for all the
motors; I can send a spline (or a sequence of splines) there, and it
will be executed.

Best,
Martin
_______________________________________________
ros-users mailing list
ros-users@code.ros.org
https://code.ros.org/mailman/listinfo/ros-users


_______________________________________________
ros-users mailing list
ros-users@code.ros.org
https://code.ros.org/mailman/listinfo/ros-users