38 #ifndef PCL_CONVERSIONS_H__
39 #define PCL_CONVERSIONS_H__
45 #include <pcl/conversions.h>
47 #include <pcl/PCLHeader.h>
50 #include <pcl/PCLImage.h>
53 #include <pcl/PCLPointField.h>
56 #include <pcl/PCLPointCloud2.h>
59 #include <pcl/PointIndices.h>
62 #include <pcl/ModelCoefficients.h>
65 #include <pcl/Vertices.h>
68 #include <pcl/PolygonMesh.h>
71 #include <pcl/io/pcd_io.h>
73 #include <Eigen/StdVector>
74 #include <Eigen/Geometry>
89 pcl_stamp = stamp.
toNSec() / 1000ull;
103 std::uint64_t pcl_stamp;
104 toPCL(stamp, pcl_stamp);
137 pcl::PCLHeader pcl_header;
148 image.
height = pcl_image.height;
149 image.
width = pcl_image.width;
150 image.
encoding = pcl_image.encoding;
152 image.
step = pcl_image.step;
159 image.
data = pcl_image.data;
166 image.
data.swap(pcl_image.data);
173 pcl_image.height = image.
height;
174 pcl_image.width = image.
width;
175 pcl_image.encoding = image.
encoding;
177 pcl_image.step = image.
step;
184 pcl_image.data = image.
data;
191 pcl_image.data.swap(image.
data);
199 pf.
name = pcl_pf.name;
200 pf.
offset = pcl_pf.offset;
202 pf.
count = pcl_pf.count;
206 void fromPCL(
const std::vector<pcl::PCLPointField> &pcl_pfs, std::vector<sensor_msgs::PointField> &pfs)
208 pfs.resize(pcl_pfs.size());
209 std::vector<pcl::PCLPointField>::const_iterator it = pcl_pfs.begin();
211 for(; it != pcl_pfs.end(); ++it, ++i) {
219 pcl_pf.name = pf.
name;
220 pcl_pf.offset = pf.
offset;
222 pcl_pf.count = pf.
count;
226 void toPCL(
const std::vector<sensor_msgs::PointField> &pfs, std::vector<pcl::PCLPointField> &pcl_pfs)
228 pcl_pfs.resize(pfs.size());
229 std::vector<sensor_msgs::PointField>::const_iterator it = pfs.begin();
231 for(; it != pfs.end(); ++it, ++i) {
232 toPCL(*(it), pcl_pfs[i]);
242 pc2.
height = pcl_pc2.height;
243 pc2.
width = pcl_pc2.width;
255 pc2.
data = pcl_pc2.data;
262 pc2.
data.swap(pcl_pc2.data);
269 pcl_pc2.height = pc2.
height;
270 pcl_pc2.width = pc2.
width;
282 pcl_pc2.data = pc2.
data;
289 pcl_pc2.data.swap(pc2.
data);
305 pi.
indices.swap(pcl_pi.indices);
319 pcl_pi.indices.swap(pi.
indices);
328 mc.
values = pcl_mc.values;
335 mc.
values.swap(pcl_mc.values);
342 pcl_mc.values = mc.
values;
349 pcl_mc.values.swap(mc.
values);
361 void fromPCL(
const std::vector<pcl::Vertices> &pcl_verts, std::vector<pcl_msgs::Vertices> &verts)
363 verts.resize(pcl_verts.size());
364 std::vector<pcl::Vertices>::const_iterator it = pcl_verts.begin();
365 std::vector<pcl_msgs::Vertices>::iterator jt = verts.begin();
366 for (; it != pcl_verts.end() && jt != verts.end(); ++it, ++jt) {
374 vert.
vertices.swap(pcl_vert.vertices);
378 void fromPCL(std::vector<pcl::Vertices> &pcl_verts, std::vector<pcl_msgs::Vertices> &verts)
380 verts.resize(pcl_verts.size());
381 std::vector<pcl::Vertices>::iterator it = pcl_verts.begin();
382 std::vector<pcl_msgs::Vertices>::iterator jt = verts.begin();
383 for (; it != pcl_verts.end() && jt != verts.end(); ++it, ++jt) {
395 void toPCL(
const std::vector<pcl_msgs::Vertices> &verts, std::vector<pcl::Vertices> &pcl_verts)
397 pcl_verts.resize(verts.size());
398 std::vector<pcl_msgs::Vertices>::const_iterator it = verts.begin();
399 std::vector<pcl::Vertices>::iterator jt = pcl_verts.begin();
400 for (; it != verts.end() && jt != pcl_verts.end(); ++it, ++jt) {
408 pcl_vert.vertices.swap(vert.
vertices);
412 void moveToPCL(std::vector<pcl_msgs::Vertices> &verts, std::vector<pcl::Vertices> &pcl_verts)
414 pcl_verts.resize(verts.size());
415 std::vector<pcl_msgs::Vertices>::iterator it = verts.begin();
416 std::vector<pcl::Vertices>::iterator jt = pcl_verts.begin();
417 for (; it != verts.end() && jt != pcl_verts.end(); ++it, ++jt) {
464 for (
size_t d = 0;
d < cloud.
fields.size(); ++
d) {
465 if (cloud.
fields[
d].name == field_name) {
466 return (
static_cast<int>(
d));
477 for (
size_t i = 0; i < cloud.
fields.size () - 1; ++i) {
478 result += cloud.
fields[i].name +
" ";
489 pcl::PCLPointCloud2 pcl_cloud;
491 pcl::PCLImage pcl_image;
492 pcl::toPCLPointCloud2(pcl_cloud, pcl_image);
499 pcl::PCLPointCloud2 pcl_cloud;
501 pcl::PCLImage pcl_image;
502 pcl::toPCLPointCloud2(pcl_cloud, pcl_image);
506 template<
typename T>
void
510 if (cloud.width == 0 && cloud.height == 0)
512 throw std::runtime_error(
"Needs to be a dense like cloud!!");
516 if (cloud.points.size () != cloud.width * cloud.height)
517 throw std::runtime_error(
"The width and height do not match the cloud size!");
518 msg.height = cloud.height;
519 msg.width = cloud.width;
523 msg.encoding =
"bgr8";
524 msg.step =
msg.width *
sizeof (std::uint8_t) * 3;
526 for (
size_t y = 0; y < cloud.height; y++)
528 for (
size_t x = 0; x < cloud.width; x++)
530 std::uint8_t * pixel = &(
msg.data[y *
msg.step + x * 3]);
531 memcpy (pixel, &cloud (x, y).rgb, 3 *
sizeof(std::uint8_t));
541 pcl::PCLPointCloud2 pcl_pc2;
542 pcl::toPCLPointCloud2(pcl_cloud, pcl_pc2);
549 pcl::PCLPointCloud2 pcl_pc2;
551 pcl::fromPCLPointCloud2(pcl_pc2, pcl_cloud);
557 pcl::PCLPointCloud2 pcl_pc2;
559 pcl::fromPCLPointCloud2(pcl_pc2, pcl_cloud);
564 template<
typename Po
intT>
565 void createMapping(
const std::vector<sensor_msgs::PointField>& msg_fields, MsgFieldMap& field_map)
567 std::vector<pcl::PCLPointField> pcl_msg_fields;
569 return createMapping<PointT>(pcl_msg_fields, field_map);
578 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
579 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
580 const bool binary_mode =
false)
582 pcl::PCLPointCloud2 pcl_cloud;
589 const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (),
590 const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (),
591 const bool binary_mode =
false)
593 pcl::PCLPointCloud2 pcl_cloud;
602 pcl::PCLPointCloud2 pcl_cloud;
630 for (
size_t i = 0; i < cloud1.
fields.size (); ++i)
631 if (cloud1.
fields[i].name ==
"_")
634 for (
size_t i = 0; i < cloud2.
fields.size (); ++i)
635 if (cloud2.
fields[i].name ==
"_")
638 if (!strip && cloud1.
fields.size () != cloud2.
fields.size ())
640 PCL_ERROR (
"[pcl::concatenatePointCloud] Number of fields in cloud1 (%u) != Number of fields in cloud2 (%u)\n", cloud1.
fields.size (), cloud2.
fields.size ());
646 size_t nrpts = cloud_out.
data.size ();
659 std::vector<sensor_msgs::PointField> fields2;
660 std::vector<int> fields2_sizes;
661 for (
size_t j = 0; j < cloud2.
fields.size (); ++j)
663 if (cloud2.
fields[j].name ==
"_")
666 fields2_sizes.push_back (cloud2.
fields[j].count *
667 pcl::getFieldSize (cloud2.
fields[j].datatype));
668 fields2.push_back (cloud2.
fields[j]);
674 for (
size_t cp = 0; cp < cloud2.
width * cloud2.
height; ++cp)
677 for (
size_t j = 0; j < fields2.size (); ++j)
679 if (cloud1.
fields[i].name ==
"_")
686 if ((cloud1.
fields[i].name ==
"rgb" && fields2[j].name ==
"rgba") ||
687 (cloud1.
fields[i].name ==
"rgba" && fields2[j].name ==
"rgb") ||
688 (cloud1.
fields[i].name == fields2[j].name))
690 memcpy (
reinterpret_cast<char*
> (&cloud_out.
data[nrpts + cp * cloud1.
point_step + cloud1.
fields[i].offset]),
700 for (
size_t i = 0; i < cloud1.
fields.size (); ++i)
703 if ((cloud1.
fields[i].name ==
"rgb" && cloud2.
fields[i].name ==
"rgba") ||
704 (cloud1.
fields[i].name ==
"rgba" && cloud2.
fields[i].name ==
"rgb"))
709 PCL_ERROR (
"[pcl::concatenatePointCloud] Name of field %d in cloud1, %s, does not match name in cloud2, %s\n", i, cloud1.
fields[i].name.c_str (), cloud2.
fields[i].name.c_str ());
713 cloud_out.
data.resize (nrpts + cloud2.
data.size ());
714 memcpy (&cloud_out.
data[nrpts], &cloud2.
data[0], cloud2.
data.size ());
728 std::shared_ptr<pcl::PCLPointCloud2>
msg(
new pcl::PCLPointCloud2());
733 namespace message_traits
739 static const char*
value(
const pcl::PCLPointCloud2&) {
return value(); }
753 static const char*
value(
const pcl::PCLPointCloud2&) {
return value(); }
760 static const char*
value(
const pcl::PCLPointCloud2&) {
return value(); }
766 namespace serialization
774 template<
typename Stream>
775 inline static void write(
Stream& stream,
const pcl::PCLPointCloud2& m)
780 stream.next(m.height);
781 stream.next(m.width);
782 std::vector<sensor_msgs::PointField> pfs;
785 stream.next(m.is_bigendian);
786 stream.next(m.point_step);
787 stream.next(m.row_step);
789 stream.next(m.is_dense);
792 template<
typename Stream>
793 inline static void read(
Stream& stream, pcl::PCLPointCloud2& m)
798 stream.next(m.height);
799 stream.next(m.width);
800 std::vector<sensor_msgs::PointField> pfs;
803 stream.next(m.is_bigendian);
804 stream.next(m.point_step);
805 stream.next(m.row_step);
807 stream.next(m.is_dense);
819 std::vector<sensor_msgs::PointField> pfs;
826 length += m.data.size() *
sizeof(std::uint8_t);
839 template<
typename Stream>
840 inline static void write(
Stream& stream,
const pcl::PCLPointField& m)
843 stream.next(m.offset);
844 stream.next(m.datatype);
845 stream.next(m.count);
848 template<
typename Stream>
849 inline static void read(
Stream& stream, pcl::PCLPointField& m)
852 stream.next(m.offset);
853 stream.next(m.datatype);
854 stream.next(m.count);
876 template<
typename Stream>
884 template<
typename Stream>