[ros-users] cartesian trajectories

Konrad Banachowicz konradb3 at gmail.com
Wed Jun 5 17:18:39 UTC 2013


I thank that messages should be strongly-typed and dislike universal
key-value message concept.
The message structure should be self-explanatory without complex context of
configuration.

The idea of trajectories for multiple end-effectors looks interesting.
What do you think about something like that :

[CartesianTrajectoryGoal]
Header header  # A stamp of 0 means "execute now"

string[] effector_names
CartesianTrajectory[] trajectory
  PoseStamped tool  # The frame which is being controlled
CartesianTrajectoryPoint[] points    duration time_from_start    Pose
pose    Twist twist
CartesianImpedance[] impedance
    TBD stiffness % cartesian stiffness
    TBD damping % damping ratio
CartesianTolerance[] path_tolerance  # Tolerance for aborting the path
 float64 position  float64 orientation  # Permitted angular error
float64 velocity  float64 angular_velocityCartesianTolerance[]
goal_tolerance  # Tolerance for when reaching the goal is considered
successful
JointTrajectory posture  # For determining the redundancy
JointImpedance nullspace_impedance # TBD




Pozdrawiam
Konrad Banachowicz


2013/6/5 Adolfo Rodríguez Tsouroukdissian <adolfo.rodriguez at pal-robotics.com
>

> Please keep the robot control sig in the loop.
>
> On Wed, Jun 5, 2013 at 5:32 PM, Georg Bartels <
> georg.bartels at cs.uni-bremen.de> wrote:
>
>> Hi guys,
>>
>> first of all: thumbs up for having this discussion on the list. It's cool
>> to have this visible for everyone. :)
>
>
> Indeed :)
>
>
>>
>>
>> On 06/05/2013 04:09 PM, Mrinal Kalakrishnan wrote:
>>
>>> Let me correct that. We actually don't use a specific
>>> "CartesianTrajectory" msg any more. Instead, we have a generic
>>> "Trajectory" msg, which has a list of dimension names and
>>> TrajectoryPoints - which makes it very similar to a JointTrajectory
>>> msg. We then agree upon a naming scheme, like "r_hand_cart_x",
>>> "r_hand_cart_force_x", and "r_hand_cart_gain_x" and so on. This allows
>>> us to synchronize the execution of cartesian positions, forces and
>>> gains (impedances), on multiple end-effectors if needed. We can also
>>> send joint trajectories (or null-space joint posture trajectories)
>>> through the same interface.
>>>
>>
>> I'd like to contribute my ideas about having one generic array-like
>> message for arbitrary types of trajectories. I think this to be a dangerous
>> idea because the meaning of "r_hand_cart_gain_x" is not communicated.
>>
>> I definitely see the appeal of having the same message outline for
>> different kinds of trajectories, but I am afraid it is inviting trouble.
>> What I mean is that it is really important to state the reference points,
>> reference frames, points of reference and frames of reference for Op-Space
>> positions, velocities and wrenches. With joint state trajectories one can
>> get away without stating such semantics because a) it's a configuration and
>> b) people usually agree on a common URDF for one robot which is not
>> mentioned in the joint state message. But Cartesian trajectories are a
>> different animal: Reference frames change a lot between applications and
>> users of the same robot. Hence, I'd vote for keeping such semantics with
>> the trajectory as partly outlined with the tool PoseStamped in
>> http://www.ros.org/wiki/robot_**mechanism_controllers/Reviews/**
>> Cartesian%20Trajectory%**20Proposal%20API%20Review<http://www.ros.org/wiki/robot_mechanism_controllers/Reviews/Cartesian%20Trajectory%20Proposal%20API%20Review>
>>
>>
> I'm not implying that semantics should be sacrificed. The semantics
> missing from the trajectory message should be present in the configuration
> of the actual interpolator, so it knows what the data represents. The
> current JointTrajectoryAction controller for example rejects trajectories
> whose joint set does not match exactly its set of controlled joints. One
> could think of a different, more complex set of checks that would validate
> and add semantic meaning to the message data. This might be easier said
> than done though. Possible complications:
> - Non-static configuration, such as your example of changing reference
> frames between messages.
> - Matching differently-sized position, velocity and acceleration
> variables. Eg, a pose represented with 7 variables (or 12, or 16), and
> twists/accelerations represented by 6.
> ...I'm probably missing others
>
> Adolfo.
>
>
>> Cheers,
>> Georg.
>>
>> ______________________________**_________________
>> ros-users mailing list
>> ros-users at code.ros.org
>> https://code.ros.org/mailman/**listinfo/ros-users<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: <http://lists.ros.org/pipermail/ros-users/attachments/20130605/360488cf/attachment-0004.html>


More information about the ros-users mailing list