30 #include <find_object_2d/ObjectsStamped.h>    31 #include <QtCore/QString>    51                 if(msg->objects.data.size())
    54                         if(targetFrameId.empty())
    56                                 targetFrameId = msg->header.frame_id;
    58                         char multiSubId = 
'b';
    60                         for(
unsigned int i=0; i<msg->objects.data.size(); i+=12)
    63                                 int id = (int)msg->objects.data[i];
    68                                         multiSuffix = QString(
"_") + multiSubId++;
    77                                 std::string objectFrameId = QString(
"%1_%2%3").arg(
objFramePrefix_.c_str()).arg(
id).arg(multiSuffix).toStdString();
    93                                 ROS_INFO(
"%s [x,y,z] [x,y,z,w] in \"%s\" frame: [%f,%f,%f] [%f,%f,%f,%f]",
    94                                                 objectFrameId.c_str(), targetFrameId.c_str(),
   108 int main(
int argc, 
char * argv[])
   110     ros::init(argc, argv, 
"tf_example_node");
 tf::TransformListener tfListener_
void objectsDetectedCallback(const find_object_2d::ObjectsStampedConstPtr &msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char *argv[])
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
std::string objFramePrefix_
std::string targetFrameId_