Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef JSK_PCL_ROS_TRANSFORM_POINTCLOUD_IN_BOUNDING_BOX_H_
00038 #define JSK_PCL_ROS_TRANSFORM_POINTCLOUD_IN_BOUNDING_BOX_H_
00039
00040 #include <pcl_ros/pcl_nodelet.h>
00041 #include <jsk_recognition_msgs/BoundingBox.h>
00042 #include <message_filters/subscriber.h>
00043 #include <message_filters/time_synchronizer.h>
00044 #include <message_filters/synchronizer.h>
00045 #include "jsk_pcl_ros/tf_listener_singleton.h"
00046 #include <eigen_conversions/eigen_msg.h>
00047 #include "jsk_pcl_ros/pcl_conversion_util.h"
00048 #include <pcl/common/transforms.h>
00049
00050 namespace jsk_pcl_ros
00051 {
00052 template <class PointT>
00053 void transformPointcloudInBoundingBox(
00054 const jsk_recognition_msgs::BoundingBox& box_msg,
00055 const sensor_msgs::PointCloud2& cloud_msg,
00056 pcl::PointCloud<PointT>& output,
00057 Eigen::Affine3f& offset,
00058 tf::TransformListener& tf_listener)
00059 {
00060 geometry_msgs::PoseStamped box_pose;
00061 box_pose.header = box_msg.header;
00062 box_pose.pose = box_msg.pose;
00063
00064 geometry_msgs::PoseStamped box_pose_respected_to_cloud;
00065 tf_listener.transformPose(cloud_msg.header.frame_id,
00066 box_pose,
00067 box_pose_respected_to_cloud);
00068
00069 Eigen::Affine3d box_pose_respected_to_cloud_eigend;
00070 tf::poseMsgToEigen(box_pose_respected_to_cloud.pose,
00071 box_pose_respected_to_cloud_eigend);
00072 Eigen::Affine3d box_pose_respected_to_cloud_eigend_inversed
00073 = box_pose_respected_to_cloud_eigend.inverse();
00074 Eigen::Matrix4f box_pose_respected_to_cloud_eigen_inversed_matrixf;
00075 Eigen::Matrix4d box_pose_respected_to_cloud_eigen_inversed_matrixd
00076 = box_pose_respected_to_cloud_eigend_inversed.matrix();
00077 convertMatrix4<Eigen::Matrix4d, Eigen::Matrix4f>(
00078 box_pose_respected_to_cloud_eigen_inversed_matrixd,
00079 box_pose_respected_to_cloud_eigen_inversed_matrixf);
00080 offset = Eigen::Affine3f(box_pose_respected_to_cloud_eigen_inversed_matrixf);
00081 pcl::PointCloud<PointT> input;
00082 pcl::fromROSMsg(cloud_msg, input);
00083 pcl::transformPointCloud(input, output, offset);
00084 }
00085
00086 class TransformPointcloudInBoundingBox: public pcl_ros::PCLNodelet
00087 {
00088 public:
00089 typedef pcl::PointXYZRGB PointT;
00090 typedef message_filters::sync_policies::ExactTime<
00091 sensor_msgs::PointCloud2,
00092 jsk_recognition_msgs::BoundingBox > SyncPolicy;
00093 protected:
00095
00097 virtual void onInit();
00098 virtual void transform(const sensor_msgs::PointCloud2::ConstPtr& msg,
00099 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
00100
00102
00104 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00105 message_filters::Subscriber<jsk_recognition_msgs::BoundingBox> sub_box_;
00106 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00107 ros::Publisher pub_cloud_;
00108 ros::Publisher pub_offset_pose_;
00109 tf::TransformListener* tf_listener_;
00110 private:
00111
00112 };
00113 }
00114
00115 #endif