A wrapper for multiple instances of a topic publisher, one for each arm in the system. More...
#include <service_action_wrappers.h>
Public Member Functions | |
MultiArmTopicWrapper (std::string prefix, std::string suffix, bool resolve_names) | |
Sets the node handle, prefix and suffix. | |
ros::Publisher & | publisher (std::string arm_name, ros::Duration timeout=ros::Duration(5.0)) |
Returns a publisher for the requested arm. | |
Private Types | |
typedef std::map< std::string, ros::Publisher > | map_type |
Private Attributes | |
ros::NodeHandle | nh_ |
The node handle used to create the publisher. | |
std::string | prefix_ |
Prefix attached to arm name to get topic name. | |
map_type | publishers_ |
The list of publishers already created, mapped to service names. | |
bool | resolve_names_ |
Whether the resulting name should first be resolved using the node handle. | |
std::string | suffix_ |
Suffix attached to arm name to get topic name. |
A wrapper for multiple instances of a topic publisher, one for each arm in the system.
This function performs mapping from an arm_name to a topic for that arm. It obtains the name of the action by adding a prefix and/or suffix to the name of the arm.
Definition at line 276 of file service_action_wrappers.h.
typedef std::map<std::string, ros::Publisher> object_manipulator::MultiArmTopicWrapper< TopicDataType >::map_type [private] |
Definition at line 288 of file service_action_wrappers.h.
object_manipulator::MultiArmTopicWrapper< TopicDataType >::MultiArmTopicWrapper | ( | std::string | prefix, |
std::string | suffix, | ||
bool | resolve_names | ||
) | [inline] |
Sets the node handle, prefix and suffix.
Definition at line 299 of file service_action_wrappers.h.
ros::Publisher& object_manipulator::MultiArmTopicWrapper< TopicDataType >::publisher | ( | std::string | arm_name, |
ros::Duration | timeout = ros::Duration(5.0) |
||
) | [inline] |
Returns a publisher for the requested arm.
Topic name is obtained as prefix + arm_name + suffix. On first request for a given arm, a publisher will be initialized. On subsequent calls for the same arm, the publisher is returned directly.
Definition at line 308 of file service_action_wrappers.h.
ros::NodeHandle object_manipulator::MultiArmTopicWrapper< TopicDataType >::nh_ [private] |
The node handle used to create the publisher.
Definition at line 280 of file service_action_wrappers.h.
std::string object_manipulator::MultiArmTopicWrapper< TopicDataType >::prefix_ [private] |
Prefix attached to arm name to get topic name.
Definition at line 283 of file service_action_wrappers.h.
map_type object_manipulator::MultiArmTopicWrapper< TopicDataType >::publishers_ [private] |
The list of publishers already created, mapped to service names.
Definition at line 291 of file service_action_wrappers.h.
bool object_manipulator::MultiArmTopicWrapper< TopicDataType >::resolve_names_ [private] |
Whether the resulting name should first be resolved using the node handle.
Use this if you are remapping topic names.
Definition at line 295 of file service_action_wrappers.h.
std::string object_manipulator::MultiArmTopicWrapper< TopicDataType >::suffix_ [private] |
Suffix attached to arm name to get topic name.
Definition at line 286 of file service_action_wrappers.h.