Go to the documentation of this file.
44 #include <sensor_msgs/Image.h>
45 #include <sensor_msgs/PointCloud2.h>
56 cloud_cb (
const sensor_msgs::PointCloud2ConstPtr& cloud)
58 if (cloud->height <= 1)
60 ROS_ERROR(
"Input point cloud is not organized, ignoring!");
66 image_.header = cloud->header;
69 catch (std::runtime_error &e)
97 main (
int argc,
char **argv)
99 ros::init (argc, argv,
"convert_pointcloud_to_image");
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
sensor_msgs::Image image_
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
std::string resolveName(const std::string &name, bool remap=true) const
void cloud_cb(const sensor_msgs::PointCloud2ConstPtr &cloud)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
#define ROS_INFO_STREAM(args)
ros::Publisher image_pub_
int main(int argc, char **argv)
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
pcl_ros
Author(s): Open Perception, Julius Kammerl
, William Woodall
autogenerated on Fri Jul 12 2024 02:54:40