36 #define BOOST_PARAMETER_MAX_ARITY 7 48 DiagnosticNodelet::onInit();
49 pub_ = advertise<sensor_msgs::PointCloud2>(
59 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
73 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
74 const sensor_msgs::Image::ConstPtr& image_msg,
75 const sensor_msgs::CameraInfo::ConstPtr& info_msg)
77 if ((cloud_msg->header.frame_id != image_msg->header.frame_id) ||
78 (cloud_msg->header.frame_id != info_msg->header.frame_id)) {
80 cloud_msg->header.frame_id.c_str(),
81 image_msg->header.frame_id.c_str(),
82 info_msg->header.frame_id.c_str());
86 pcl::PointCloud<pcl::PointXYZ>::Ptr
cloud 87 (
new pcl::PointCloud<pcl::PointXYZ>);
90 pcl::PointCloud<pcl::PointXYZRGB>::Ptr rgb_cloud
91 (
new pcl::PointCloud<pcl::PointXYZRGB>);
92 rgb_cloud->points.resize(cloud->points.size());
93 rgb_cloud->is_dense = cloud->is_dense;
94 rgb_cloud->width = cloud->width;
95 rgb_cloud->height = cloud->height;
100 for (
size_t i = 0; i < cloud->points.size(); i++) {
102 p.x = cloud->points[i].x;
103 p.y = cloud->points[i].y;
104 p.z = cloud->points[i].z;
106 if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
109 if (uv.x > 0 && uv.x < image_msg->width &&
110 uv.y > 0 && uv.y < image_msg->height) {
111 cv::Vec3b
rgb = image.at<cv::Vec3b>(uv.y, uv.x);
117 rgb_cloud->points[i] = p;
119 sensor_msgs::PointCloud2 ros_cloud;
121 ros_cloud.header = cloud_msg->header;
void publish(const boost::shared_ptr< M > &message) const
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::AddColorFromImage, nodelet::Nodelet)
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
virtual void unsubscribe()
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
message_filters::Subscriber< sensor_msgs::Image > sub_image_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
cv::Point2d project3dToPixel(const cv::Point3d &xyz) const
#define NODELET_FATAL(...)
virtual void addColor(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::CameraInfo::ConstPtr &info_msg)
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_