41 #include <posedetection_msgs/ObjectDetection.h> 
   52                        const geometry_msgs::Pose& pose2,
 
   54                        Eigen::Quaterniond& rot)
 
   56   Eigen::Affine3d affine1, affine2;
 
   61   Eigen::Affine3d transform = affine1 * affine2.inverse();
 
   62   pos = Eigen::Vector3d(transform.translation());
 
   63   rot = Eigen::Quaterniond(transform.rotation());
 
   67 void callback(
const posedetection_msgs::ObjectDetection::ConstPtr& detection1,
 
   68               const posedetection_msgs::ObjectDetection::ConstPtr& detection2)
 
   70   if (detection1->objects.size() > 0 && detection2->objects.size() > 0) {
 
   71     geometry_msgs::Pose pose1 = detection1->objects[0].pose;
 
   72     geometry_msgs::Pose pose2 = detection2->objects[0].pose;
 
   74     Eigen::Quaterniond rot;
 
   77     ROS_INFO(
"  pos: [%f %f %f]", pos[0], pos[1], pos[2]);
 
   78     ROS_INFO(
"  rot: [%f %f %f %f]", rot.x(), rot.y(), rot.z(), rot.w());
 
   79     if (detection1->header.frame_id != detection2->header.frame_id) {
 
   80       geometry_msgs::PoseStamped pose2_stamped, pose2_stamped_transformed;
 
   81       pose2_stamped.header = detection2->header;
 
   82       pose2_stamped.pose = pose2;
 
   86                                    pose2_stamped_transformed);
 
   87         geometry_msgs::Pose pose2_transformed = pose2_stamped_transformed.pose;
 
   88         Eigen::Vector3d pos_transformed;
 
   89         Eigen::Quaterniond rot_transformed;
 
   92         geometry_msgs::PoseStamped pose_out;
 
   93         pose_out.header.stamp = detection2->header.stamp;
 
   95         pose_out.pose.position.x = pos_transformed[0];
 
   96         pose_out.pose.position.y = pos_transformed[1];
 
   97         pose_out.pose.position.z = pos_transformed[2];
 
   98         pose_out.pose.orientation.x = rot_transformed.x();
 
   99         pose_out.pose.orientation.y = rot_transformed.y();
 
  100         pose_out.pose.orientation.z = rot_transformed.z();
 
  101         pose_out.pose.orientation.w = rot_transformed.w();
 
  105         ROS_INFO(
"  pos: [%f %f %f]", pos_transformed[0], pos_transformed[1], pos_transformed[2]);
 
  106         ROS_INFO(
"  rot: [%f %f %f %f]", rot_transformed.x(), rot_transformed.y(), rot_transformed.z(), rot_transformed.w());
 
  109         ROS_ERROR(
"failed to resolve tf: %s", e.what());
 
  112         ROS_ERROR(
"failed to resolve tf: %s", e.what());
 
  115         ROS_ERROR(
"failed to resolve tf: %s", e.what());
 
  123 int main(
int argc, 
char** argv)
 
  125   ros::init(argc, argv, 
"objectdetection_transform_echo");
 
  128     posedetection_msgs::ObjectDetection, posedetection_msgs::ObjectDetection>
 
  138     detection1_sub(nh, 
"detection1", 1);
 
  140     detection2_sub(nh, 
"detection2", 1);
 
  144     detection1_sub, detection2_sub);