37 #include <pcl/visualization/common/float_image_utils.h> 45 float min_range, max_range;
46 range_image.getMinMaxRanges(min_range, max_range);
47 float min_max_range = max_range - min_range;
49 image = cv::Mat(range_image.height, range_image.width, CV_8UC3);
51 for (
int y=0;
y < range_image.height;
y++) {
52 for (
int x=0;
x<range_image.width;
x++) {
53 pcl::PointWithRange rangePt = range_image.getPoint(
x,
y);
54 if (!pcl_isfinite(rangePt.range)) {
55 pcl::visualization::FloatImageUtils::getColorForFloat(
56 rangePt.range, r, g, b);
59 float value = (rangePt.range - min_range) / min_max_range;
60 pcl::visualization::FloatImageUtils::getColorForFloat(
63 image.at<cv::Vec3b>(
y,
x)[0] = b;
64 image.at<cv::Vec3b>(y,
x)[1] = g;
65 image.at<cv::Vec3b>(y,
x)[2] = r;
74 Eigen::Matrix4d from_mat = from.matrix();
75 Eigen::Matrix4f to_mat;
76 convertMatrix4<Eigen::Matrix4d, Eigen::Matrix4f>(from_mat, to_mat);
77 to = Eigen::Affine3f(to_mat);
83 Eigen::Matrix4f from_mat = from.matrix();
84 Eigen::Matrix4d to_mat;
85 convertMatrix4<Eigen::Matrix4f, Eigen::Matrix4d>(from_mat, to_mat);
86 to = Eigen::Affine3d(to_mat);
92 std::vector<pcl::PointIndices::Ptr>
94 const std::vector<PCLIndicesMsg>& cluster_indices)
96 std::vector<pcl::PointIndices::Ptr> ret;
97 for (
size_t i = 0; i < cluster_indices.size(); i++) {
98 std::vector<int> indices = cluster_indices[i].indices;
99 pcl::PointIndices::Ptr pcl_indices (
new pcl::PointIndices);
100 pcl_indices->indices = indices;
101 ret.push_back(pcl_indices);
106 std::vector<pcl::ModelCoefficients::Ptr>
108 const std::vector<PCLModelCoefficientMsg>& coefficients)
110 std::vector<pcl::ModelCoefficients::Ptr> ret;
111 for (
size_t i = 0; i < coefficients.size(); i++) {
112 pcl::ModelCoefficients::Ptr pcl_coefficients (
new pcl::ModelCoefficients);
113 pcl_coefficients->values = coefficients[i].values;
114 ret.push_back(pcl_coefficients);
119 std::vector<PCLIndicesMsg>
121 const std::vector<pcl::PointIndices::Ptr> cluster_indices,
122 const std_msgs::Header&
header)
124 std::vector<PCLIndicesMsg> ret;
125 for (
size_t i = 0; i < cluster_indices.size(); i++) {
128 ros_msg.indices = cluster_indices[i]->indices;
129 ret.push_back(ros_msg);
134 std::vector<PCLIndicesMsg>
136 const std::vector<pcl::PointIndices> cluster_indices,
137 const std_msgs::Header&
header)
139 std::vector<PCLIndicesMsg> ret;
140 for (
size_t i = 0; i < cluster_indices.size(); i++) {
143 ros_msg.indices = cluster_indices[i].indices;
144 ret.push_back(ros_msg);
149 std::vector<PCLModelCoefficientMsg>
151 const std::vector<pcl::ModelCoefficients::Ptr>& coefficients,
152 const std_msgs::Header&
header)
154 std::vector<PCLModelCoefficientMsg> ret;
155 for (
size_t i = 0; i < coefficients.size(); i++) {
158 ros_msg.values = coefficients[i]->values;
159 ret.push_back(ros_msg);
171 Eigen::Affine3d eigen_d;
178 Eigen::Affine3d eigen_d;
185 Eigen::Affine3d eigen_d;
192 Eigen::Affine3d eigen_d;
199 Eigen::Affine3d eigen_d;
206 Eigen::Affine3d eigen_d;
222 Eigen::Vector3d
d(e[0], e[1], e[2]);
void transformEigenToMsg(Eigen::Affine3f &eigen, geometry_msgs::Transform &msg)
void transformEigenToTF(Eigen::Affine3f &eigen, tf::Transform &t)
std::vector< PCLModelCoefficientMsg > convertToROSModelCoefficients(const std::vector< pcl::ModelCoefficients::Ptr > &coefficients, const std_msgs::Header &header)
std::vector< pcl::ModelCoefficients::Ptr > convertToPCLModelCoefficients(const std::vector< PCLModelCoefficientMsg > &coefficients)
void poseMsgToEigen(const geometry_msgs::Pose &msg, Eigen::Affine3f &eigen)
void vectorEigenToTF(const Eigen::Vector3d &e, tf::Vector3 &t)
std::vector< pcl::PointIndices::Ptr > convertToPCLPointIndices(const std::vector< PCLIndicesMsg > &cluster_indices)
void transformMsgToEigen(const geometry_msgs::Transform &msg, Eigen::Affine3f &eigen)
void rangeImageToCvMat(const pcl::RangeImage &range_image, cv::Mat &mat)
Convert pcl::RangeImage to cv::Mat. Distance is normalized to 0-1 and colorized.
void convertEigenAffine3(const Eigen::Affine3d &from, Eigen::Affine3f &to)
std::vector< PCLIndicesMsg > convertToROSPointIndices(const std::vector< pcl::PointIndices::Ptr > cluster_indices, const std_msgs::Header &header)
void poseEigenToMsg(Eigen::Affine3f &eigen, geometry_msgs::Pose &msg)
void vectorTFToEigen(const tf::Vector3 &t, Eigen::Vector3d &e)
void vectorEigenToTF(const Eigen::Vector3f &e, tf::Vector3 &t)
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3f &eigen)
pcl::PointIndices PCLIndicesMsg
void vectorTFToEigen(const tf::Vector3 &t, Eigen::Vector3f &e)
pcl::ModelCoefficients PCLModelCoefficientMsg