00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include "jsk_recognition_utils/pcl_conversion_util.h"
00037 #include <pcl/visualization/common/float_image_utils.h>
00038
00039 namespace jsk_recognition_utils
00040 {
00041
00042 void rangeImageToCvMat(const pcl::RangeImage& range_image,
00043 cv::Mat& image)
00044 {
00045 float min_range, max_range;
00046 range_image.getMinMaxRanges(min_range, max_range);
00047 float min_max_range = max_range - min_range;
00048
00049 image = cv::Mat(range_image.height, range_image.width, CV_8UC3);
00050 unsigned char r,g,b;
00051 for (int y=0; y < range_image.height; y++) {
00052 for (int x=0; x<range_image.width; x++) {
00053 pcl::PointWithRange rangePt = range_image.getPoint(x,y);
00054 if (!pcl_isfinite(rangePt.range)) {
00055 pcl::visualization::FloatImageUtils::getColorForFloat(
00056 rangePt.range, r, g, b);
00057 }
00058 else {
00059 float value = (rangePt.range - min_range) / min_max_range;
00060 pcl::visualization::FloatImageUtils::getColorForFloat(
00061 value, r, g, b);
00062 }
00063 image.at<cv::Vec3b>(y,x)[0] = b;
00064 image.at<cv::Vec3b>(y,x)[1] = g;
00065 image.at<cv::Vec3b>(y,x)[2] = r;
00066 }
00067 }
00068 return;
00069 }
00070
00071 void convertEigenAffine3(const Eigen::Affine3d& from,
00072 Eigen::Affine3f& to)
00073 {
00074 Eigen::Matrix4d from_mat = from.matrix();
00075 Eigen::Matrix4f to_mat;
00076 convertMatrix4<Eigen::Matrix4d, Eigen::Matrix4f>(from_mat, to_mat);
00077 to = Eigen::Affine3f(to_mat);
00078 }
00079
00080 void convertEigenAffine3(const Eigen::Affine3f& from,
00081 Eigen::Affine3d& to)
00082 {
00083 Eigen::Matrix4f from_mat = from.matrix();
00084 Eigen::Matrix4d to_mat;
00085 convertMatrix4<Eigen::Matrix4f, Eigen::Matrix4d>(from_mat, to_mat);
00086 to = Eigen::Affine3d(to_mat);
00087 }
00088 }
00089
00090 namespace pcl_conversions
00091 {
00092 std::vector<pcl::PointIndices::Ptr>
00093 convertToPCLPointIndices(
00094 const std::vector<PCLIndicesMsg>& cluster_indices)
00095 {
00096 std::vector<pcl::PointIndices::Ptr> ret;
00097 for (size_t i = 0; i < cluster_indices.size(); i++) {
00098 std::vector<int> indices = cluster_indices[i].indices;
00099 pcl::PointIndices::Ptr pcl_indices (new pcl::PointIndices);
00100 pcl_indices->indices = indices;
00101 ret.push_back(pcl_indices);
00102 }
00103 return ret;
00104 }
00105
00106 std::vector<pcl::ModelCoefficients::Ptr>
00107 convertToPCLModelCoefficients(
00108 const std::vector<PCLModelCoefficientMsg>& coefficients)
00109 {
00110 std::vector<pcl::ModelCoefficients::Ptr> ret;
00111 for (size_t i = 0; i < coefficients.size(); i++) {
00112 pcl::ModelCoefficients::Ptr pcl_coefficients (new pcl::ModelCoefficients);
00113 pcl_coefficients->values = coefficients[i].values;
00114 ret.push_back(pcl_coefficients);
00115 }
00116 return ret;
00117 }
00118
00119 std::vector<PCLIndicesMsg>
00120 convertToROSPointIndices(
00121 const std::vector<pcl::PointIndices::Ptr> cluster_indices,
00122 const std_msgs::Header& header)
00123 {
00124 std::vector<PCLIndicesMsg> ret;
00125 for (size_t i = 0; i < cluster_indices.size(); i++) {
00126 PCLIndicesMsg ros_msg;
00127 ros_msg.header = header;
00128 ros_msg.indices = cluster_indices[i]->indices;
00129 ret.push_back(ros_msg);
00130 }
00131 return ret;
00132 }
00133
00134 std::vector<PCLIndicesMsg>
00135 convertToROSPointIndices(
00136 const std::vector<pcl::PointIndices> cluster_indices,
00137 const std_msgs::Header& header)
00138 {
00139 std::vector<PCLIndicesMsg> ret;
00140 for (size_t i = 0; i < cluster_indices.size(); i++) {
00141 PCLIndicesMsg ros_msg;
00142 ros_msg.header = header;
00143 ros_msg.indices = cluster_indices[i].indices;
00144 ret.push_back(ros_msg);
00145 }
00146 return ret;
00147 }
00148
00149 std::vector<PCLModelCoefficientMsg>
00150 convertToROSModelCoefficients(
00151 const std::vector<pcl::ModelCoefficients::Ptr>& coefficients,
00152 const std_msgs::Header& header)
00153 {
00154 std::vector<PCLModelCoefficientMsg> ret;
00155 for (size_t i = 0; i < coefficients.size(); i++) {
00156 PCLModelCoefficientMsg ros_msg;
00157 ros_msg.header = header;
00158 ros_msg.values = coefficients[i]->values;
00159 ret.push_back(ros_msg);
00160 }
00161 return ret;
00162 }
00163
00164 }
00165
00166
00167 namespace tf
00168 {
00169 void poseMsgToEigen(const geometry_msgs::Pose& msg, Eigen::Affine3f& eigen)
00170 {
00171 Eigen::Affine3d eigen_d;
00172 poseMsgToEigen(msg, eigen_d);
00173 jsk_recognition_utils::convertEigenAffine3(eigen_d, eigen);
00174 }
00175
00176 void poseEigenToMsg(Eigen::Affine3f& eigen, geometry_msgs::Pose& msg)
00177 {
00178 Eigen::Affine3d eigen_d;
00179 jsk_recognition_utils::convertEigenAffine3(eigen, eigen_d);
00180 poseEigenToMsg(eigen_d, msg);
00181 }
00182
00183 void transformMsgToEigen(const geometry_msgs::Transform& msg, Eigen::Affine3f& eigen)
00184 {
00185 Eigen::Affine3d eigen_d;
00186 transformMsgToEigen(msg, eigen_d);
00187 jsk_recognition_utils::convertEigenAffine3(eigen_d, eigen);
00188 }
00189
00190 void transformEigenToMsg(Eigen::Affine3f& eigen, geometry_msgs::Transform& msg)
00191 {
00192 Eigen::Affine3d eigen_d;
00193 jsk_recognition_utils::convertEigenAffine3(eigen_d, eigen);
00194 transformEigenToMsg(eigen_d, msg);
00195 }
00196
00197 void transformTFToEigen(const tf::Transform& t, Eigen::Affine3f& eigen)
00198 {
00199 Eigen::Affine3d eigen_d;
00200 transformTFToEigen(t, eigen_d);
00201 jsk_recognition_utils::convertEigenAffine3(eigen_d, eigen);
00202 }
00203
00204 void transformEigenToTF(Eigen::Affine3f& eigen , tf::Transform& t)
00205 {
00206 Eigen::Affine3d eigen_d;
00207 jsk_recognition_utils::convertEigenAffine3(eigen, eigen_d);
00208 transformEigenToTF(eigen_d, t);
00209 }
00210
00211 void vectorTFToEigen(const tf::Vector3& t, Eigen::Vector3f& e)
00212 {
00213 Eigen::Vector3d d;
00214 tf::vectorTFToEigen(t, d);
00215 e[0] = d[0];
00216 e[1] = d[1];
00217 e[2] = d[2];
00218 }
00219
00220 void vectorEigenToTF(const Eigen::Vector3f& e, tf::Vector3& t)
00221 {
00222 Eigen::Vector3d d(e[0], e[1], e[2]);
00223 tf::vectorEigenToTF(d, t);
00224 }
00225 }