6 #include <sensor_msgs/Image.h> 20 PointCloud::ConstPtr
const& pointCloud)
22 auto texturedPointCloud = boost::make_shared<TexturedPointCloud>();
24 if (static_cast<int>(pointCloud->width) != image.cols ||
static_cast<int>(pointCloud->height) != image.rows)
26 ROS_ERROR(
"The point cloud does not have the same format as the rectified " 28 return texturedPointCloud;
31 texturedPointCloud->header.frame_id = pointCloud->header.frame_id;
32 texturedPointCloud->header.stamp = pointCloud->header.stamp;
34 texturedPointCloud->is_dense = pointCloud->is_dense;
35 texturedPointCloud->width = pointCloud->width;
36 texturedPointCloud->height = pointCloud->height;
37 texturedPointCloud->points.resize(texturedPointCloud->width * texturedPointCloud->height);
39 for (
size_t x = 0;
x < pointCloud->width;
x++)
41 for (
size_t y = 0;
y < pointCloud->height;
y++)
43 auto& point = texturedPointCloud->at(
x,
y);
45 point.x = pointCloud->at(
x,
y).x;
46 point.y = pointCloud->at(
x,
y).y;
47 point.z = pointCloud->at(
x,
y).z;
49 if (image.channels() == 3)
51 cv::Vec3b color = image.at<cv::Vec3b>(
y,
x);
52 point.b = color.val[0];
53 point.g = color.val[1];
54 point.r = color.val[2];
58 uchar color = image.at<uchar>(
y,
x);
66 return texturedPointCloud;
97 std::lock_guard<std::mutex> lock(mutex);
104 std::lock_guard<std::mutex> lock(mutex);
106 latestPointCloud = pointCloud;
112 if (!latestImage.get() || !latestPointCloud.get())
122 ROS_ERROR(
"cv_bridge exception: %s", e.what());
125 TexturedPointCloud::Ptr texturedPointCloud;
128 texturedPointCloudPublisher.
publish(texturedPointCloud);
132 int main(
int argc,
char** argv)
134 ros::init(argc, argv,
"texture_point_cloud");
sensor_msgs::ImageConstPtr latestImage
PointCloud::ConstPtr latestPointCloud
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
image_transport::Subscriber imageSubscriber
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
sensor_msgs::PointCloud2 PointCloud
TFSIMD_FORCE_INLINE const tfScalar & y() const
ros::Subscriber pointCloudSubscriber
ROSCPP_DECL void spin(Spinner &spinner)
void onImageReceived(sensor_msgs::ImageConstPtr const &image)
pcl::PointCloud< pcl::PointXYZRGB > TexturedPointCloud
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void onPointCloudReceived(PointCloud::ConstPtr const &pointCloud)
TexturedPointCloud::Ptr texturePointCloudFromRectifiedImage(cv::Mat const &image, PointCloud::ConstPtr const &pointCloud)
ros::NodeHandle nodeHandle
ros::Publisher texturedPointCloudPublisher