28 #include <rclcpp/rclcpp.hpp>    31 #include <find_object_2d/msg/objects_stamped.hpp>    32 #include <geometry_msgs/msg/transform_stamped.hpp>    33 #include <QtCore/QString>    39                 Node(
"tf_example_node"),
    42                 tfBuffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock());
    47                 tfListener_ = std::make_shared<tf2_ros::TransformListener>(*tfBuffer_);
    52                 subs_ = create_subscription<find_object_2d::msg::ObjectsStamped>(
"objectsStamped", rclcpp::QoS(5).reliability((rmw_qos_reliability_policy_t)1), std::bind(&
TfExample::objectsDetectedCallback, 
this, std::placeholders::_1));
    59                 if(msg->objects.data.size())
    62                         if(targetFrameId.empty())
    64                                 targetFrameId = msg->header.frame_id;
    66                         char multiSubId = 
'b';
    68                         for(
unsigned int i=0; i<msg->objects.data.size(); i+=12)
    71                                 int id = (int)msg->objects.data[i];
    76                                         multiSuffix = QString(
"_") + multiSubId++;
    85                                 std::string objectFrameId = QString(
"%1_%2%3").arg(
objFramePrefix_.c_str()).arg(
id).arg(multiSuffix).toStdString();
    87                                 geometry_msgs::msg::TransformStamped pose;
    92                                         pose = 
tfBuffer_->lookupTransform(targetFrameId, objectFrameId, tf2_ros::fromMsg(msg->header.stamp));
    96                                         RCLCPP_WARN(this->get_logger(), 
"%s",ex.what());
   101                                 RCLCPP_INFO(this->get_logger(), 
"%s [x,y,z] [x,y,z,w] in \"%s\" frame: [%f,%f,%f] [%f,%f,%f,%f]",
   102                                                 objectFrameId.c_str(), targetFrameId.c_str(),
   103                                                 pose.transform.translation.x, pose.transform.translation.y, pose.transform.translation.z,
   104                                                 pose.transform.rotation.x, pose.transform.rotation.y, pose.transform.rotation.z, pose.transform.rotation.w);
   112         rclcpp::Subscription<find_object_2d::msg::ObjectsStamped>::SharedPtr 
subs_;
   117 int main(
int argc, 
char * argv[])
   119         rclcpp::init(argc, argv);
   120         rclcpp::spin(std::make_shared<TfExample>());
 tf::TransformListener tfListener_
void objectsDetectedCallback(const find_object_2d::ObjectsStampedConstPtr &msg)
void objectsDetectedCallback(const find_object_2d::msg::ObjectsStamped::ConstSharedPtr msg)
rclcpp::Subscription< find_object_2d::msg::ObjectsStamped >::SharedPtr subs_
int main(int argc, char *argv[])
std::shared_ptr< tf2_ros::Buffer > tfBuffer_
std::string objFramePrefix_
std::shared_ptr< tf2_ros::TransformListener > tfListener_
std::string targetFrameId_