Go to the documentation of this file.
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");
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
std::string objFramePrefix_
std::string targetFrameId_
void objectsDetectedCallback(const find_object_2d::ObjectsStampedConstPtr &msg)
int main(int argc, char *argv[])
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
tf::TransformListener tfListener_
T param(const std::string ¶m_name, const T &default_val) const
find_object_2d
Author(s): Mathieu Labbe
autogenerated on Mon Dec 12 2022 03:43:35