#include <ObjectTFBroadcaster.h>
Public Member Functions | |
bool | isRegistered (const std::string &name) const |
ObjectTFBroadcaster (ros::NodeHandle &n, const std::string ®ister_object_service, unsigned int publish_tf_rate, unsigned int query_object_info_rate, const std::string &object_topic, const std::string &object_service) | |
int | registerObject (const std::string &name, bool printMsgs=true) |
Private Member Functions | |
void | objectCallback (const object_msgs::Object &obj) |
void | publishTFEvent (const ros::TimerEvent &e) |
bool | queryObjectPose (const std::string &name, object_msgs::Object &obj, bool printErrors=true) |
void | queryObjectPoseEvent (const ros::TimerEvent &e) |
bool | registerObjectService (object_msgs::RegisterObject::Request &req, object_msgs::RegisterObject::Response &res) |
void | sendTF (const geometry_msgs::PoseStamped &pose, const std::string &frame_name) |
bool | updateObject (const object_msgs::Object &obj) |
Private Attributes | |
ros::NodeHandle | node |
std::map< std::string, geometry_msgs::PoseStamped > | obj_poses |
boost::recursive_mutex | obj_poses_mutex |
ros::ServiceClient | object_info_srv |
ros::Subscriber | object_info_sub |
ros::Timer | publish_tf_timer |
ros::Timer | query_object_info_timer |
ros::ServiceServer | register_object_srv |
tf::TransformBroadcaster | tf_broadcaster |
Subscribes to object_msgs/Object topic or uses the object_msgs/ObjectInfo service to query information about objects, and then broadcasts the information as /tf transform. Only objects which have been explicitly registered with registerObject() are processed. Only objects which arrive or are queried with the service and have a Object.header.frame_id which is **not empty** are considered valid and are processed.
Refer to the constructor for more information about how it works.
Definition at line 24 of file ObjectTFBroadcaster.h.
ObjectTFBroadcaster::ObjectTFBroadcaster | ( | ros::NodeHandle & | n, |
const std::string & | register_object_service, | ||
unsigned int | publish_tf_rate, | ||
unsigned int | query_object_info_rate, | ||
const std::string & | object_topic, | ||
const std::string & | object_service | ||
) |
Constructor. Parameters describe how the ObjectTFBRoadcaster works.
register_object_service | the name under which a service of type object_msgs/RegisterObject is going to be provided which can be used to add objects to be published wiht /tf. |
query_object_info_rate | when using the object_msgs/ObjectInfo service to obtain object information, this is the rate at which this is done. If no service is to be used, and instead it should be relied on messages published on object_topic only, then object_service should be left empty, and query_object_info_rate will be ignored. |
publish_tf_rate | rate at which to publish information to /tf. This may differ from the query_object_info_rate, i.e. it may be set higer, in order to keep refreshing the timestamps of the /tf tree. Because it is expected that objects don't change their state very often, query_object_info_rate (or the rate at which object messages arrive at object_topic) can be lower. |
object_topic | the topic at which object_msgs/Object information is being published. Can be left empty to instead rely on object_service |
object_service | the object_msgs/ObjectInfo service where information about objects can be queried. Can be left empty to rely on messages being published on object_topic. The service is queried at query_object_info_rate. |
Definition at line 7 of file ObjectTFBroadcaster.cpp.
bool ObjectTFBroadcaster::isRegistered | ( | const std::string & | name | ) | const |
Definition at line 41 of file ObjectTFBroadcaster.cpp.
void ObjectTFBroadcaster::objectCallback | ( | const object_msgs::Object & | obj | ) | [private] |
Callback for subscriber to object_msgs/Object
Definition at line 142 of file ObjectTFBroadcaster.cpp.
void ObjectTFBroadcaster::publishTFEvent | ( | const ros::TimerEvent & | e | ) | [private] |
Event loop for publishing tf
Definition at line 146 of file ObjectTFBroadcaster.cpp.
bool ObjectTFBroadcaster::queryObjectPose | ( | const std::string & | name, |
object_msgs::Object & | obj, | ||
bool | printErrors = true |
||
) | [private] |
Uses the service to request object information (only pose)
Definition at line 88 of file ObjectTFBroadcaster.cpp.
void ObjectTFBroadcaster::queryObjectPoseEvent | ( | const ros::TimerEvent & | e | ) | [private] |
Event loop for querying the newest object information
Definition at line 159 of file ObjectTFBroadcaster.cpp.
int ObjectTFBroadcaster::registerObject | ( | const std::string & | name, |
bool | printMsgs = true |
||
) |
return code as in object_msgs::RegisterObject
Definition at line 62 of file ObjectTFBroadcaster.cpp.
bool ObjectTFBroadcaster::registerObjectService | ( | object_msgs::RegisterObject::Request & | req, |
object_msgs::RegisterObject::Response & | res | ||
) | [private] |
service callback
Definition at line 49 of file ObjectTFBroadcaster.cpp.
void ObjectTFBroadcaster::sendTF | ( | const geometry_msgs::PoseStamped & | pose, |
const std::string & | frame_name | ||
) | [private] |
This transform (pose) holds for the target frame frame_name
Definition at line 109 of file ObjectTFBroadcaster.cpp.
bool ObjectTFBroadcaster::updateObject | ( | const object_msgs::Object & | obj | ) | [private] |
Updates information of this object in the map.
Definition at line 120 of file ObjectTFBroadcaster.cpp.
Definition at line 110 of file ObjectTFBroadcaster.h.
std::map<std::string, geometry_msgs::PoseStamped> object_msgs_tools::ObjectTFBroadcaster::obj_poses [private] |
Definition at line 103 of file ObjectTFBroadcaster.h.
boost::recursive_mutex object_msgs_tools::ObjectTFBroadcaster::obj_poses_mutex [mutable, private] |
Definition at line 104 of file ObjectTFBroadcaster.h.
Definition at line 107 of file ObjectTFBroadcaster.h.
Definition at line 108 of file ObjectTFBroadcaster.h.
Definition at line 113 of file ObjectTFBroadcaster.h.
Definition at line 114 of file ObjectTFBroadcaster.h.
Definition at line 106 of file ObjectTFBroadcaster.h.
Definition at line 112 of file ObjectTFBroadcaster.h.