Ben, I'm not sure that there's a recommended way to handle multiple goal types as this is something that we haven't done with great regularity, but I can try to give insight on the options and their trade-offs so that you can make the decision that's best for you. Option 1 - Having extra fields in the .action file: We've used this approach for the grasping pipeline that we've built here at Willow and it seems to work pretty well. A clear disadvantage is that you have an .action file that contains more information than it strictly needs to and you need to check somehow which interface the user wants rather than having a separate type. Some might argue that this is also not as clean as providing two interfaces on separate ROS channels (in this case over the action protocol), but it also helps avoid race conditions that can occur from having two separate channels. Option 2 - Two .action files and two action servers: Actionlib doesn't have support for multiple goal types by default, though you could build tools for handling this on top of the current protocol. The benefit here is that you have two clearly separated ROS interfaces, but the disadvantage is that you have to deal with a whole bunch of race conditions in how you want to process goals. You also have to handle the interaction between the two action servers.... like preempting a goal in one when a new one comes in over the wire for the other. Given the programming pain that comes along with this, we haven't actually used this option in practice... though it should be doable. Option 3 - Conversion on the client side: Another option is to expose only one interface from the server, but to provide conversion utilities on the client side that make it easy to convert from a second type to the one the server requires. This assumes that there is a clear conversion procedure between the two desired goal types, but may work well in many cases. Hope this helps, Eitan On Thu, Sep 16, 2010 at 10:22 AM, Axelrod, Benjamin wrote: > What is the recommended way to handle multiple goal types with > actionlib? > > 1) Put flags in the .action file such that it can handle multiple > goal types? This means always have a single action file for each > server/client pair. > > 2) Make two different .action files: > > a. Can a single server/client pair handle multiple .action files? > > b. Should you have 2 actionlib servers and 2 actionlib clients? And > if so, how can they interact? > > > > For example, suppose you have a node which drives a simple differential > drive robot base. You want this server to take either a drive straight > distance, or the number of degrees to rotate in place. Both actions can’t > be going at the same time. A new goal of one type should preempt the > other. And the goal specification, feedback, and result are different > enough that it might make a single .action file rather awkward. > > > > I could imagine a single .action file such as: > > > > float32 driveStraightDistance > > float32 rotateDegrees > > bool driveStraight #true to drive straight, false to rotate > > --- > > float32 metersTraveled > > float32 degreesRotated > > bool driveStraight #true if this goal was for a drive straight command > > --- > > float32 metersTraveled > > float32 degreesRotated > > bool driveStraight #true if this goal was for a drive straight command > > > > Of course there are some redundant fields there. This isn’t my exact use > case, but you get the idea… > > > > Thanks, > > -Ben > > > > > > > > -- > > Ben Axelrod > > Research Scientist > > iRobot Corporation > > 8 Crosby Drive, Mail Stop 8-1 > > Bedford, MA 01730 > > (781) 430-3315 (Tel) > > (781) 960-2628 (Fax) > > baxelrod@irobot.com > > > > _______________________________________________ > ros-users mailing list > ros-users@code.ros.org > https://code.ros.org/mailman/listinfo/ros-users > >