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
00033 #ifndef IMAGE_TOOLS_H
00034 #define IMAGE_TOOLS_H
00035
00036 #include <cstring>
00037
00038 #include <sensor_msgs/Image.h>
00039 #include <sensor_msgs/CameraInfo.h>
00040 #include <sensor_msgs/PointCloud2.h>
00041
00042 #include <stereo_msgs/DisparityImage.h>
00043
00044 #include <cmath>
00045
00046 namespace rviz_interaction_tools {
00047
00049 inline void getPoint(const sensor_msgs::PointCloud2 &cloud,
00050 unsigned int h, unsigned int w, float &x, float &y, float &z)
00051 {
00052 ROS_ASSERT(h<cloud.height && w<cloud.width);
00053 memcpy(&x, &(cloud.data.at(h*cloud.row_step + w*cloud.point_step)), sizeof(float));
00054 memcpy(&y, &(cloud.data.at(h*cloud.row_step + w*cloud.point_step + sizeof(float))), sizeof(float));
00055 memcpy(&z, &(cloud.data.at(h*cloud.row_step + w*cloud.point_step + 2*sizeof(float))), sizeof(float));
00056 }
00057
00059 inline bool hasPoint(const sensor_msgs::PointCloud2 &cloud, unsigned int h, unsigned int w)
00060 {
00061 ROS_ASSERT(h<cloud.height || w<cloud.width);
00062 float x;
00063 memcpy(&x, &(cloud.data.at(h*cloud.row_step + w*cloud.point_step)), sizeof(float));
00064 if (std::isnan(x) || std::isinf(x)) return false;
00065 return true;
00066 }
00067
00069 inline void getValue(const sensor_msgs::Image &image, unsigned int h, unsigned int w, float &val)
00070 {
00071 ROS_ASSERT(h<image.height && w<image.width);
00072 memcpy(&val, &(image.data.at( h*image.step + sizeof(float)*w )), sizeof(float));
00073 }
00074
00076 inline void setValue(sensor_msgs::Image &image, unsigned int h, unsigned int w,
00077 float val)
00078 {
00079 ROS_ASSERT(h<image.height && w<image.width);
00080 memcpy(&(image.data.at( h*image.step + sizeof(float)*w )), &val, sizeof(float));
00081 }
00082
00084 inline bool hasPoint(const sensor_msgs::Image &image, unsigned int h, unsigned int w)
00085 {
00086 ROS_ASSERT(h<image.height && w<image.width);
00087 float val;
00088 memcpy(&val, &(image.data.at( h*image.step + sizeof(float)*w )), sizeof(float));
00089 if (std::isnan(val) || std::isinf(val)) return false;
00090 return true;
00091 }
00092
00094 inline bool hasDisparityValue(const stereo_msgs::DisparityImage &disparity_image, unsigned int h, unsigned int w)
00095 {
00096 ROS_ASSERT(h<disparity_image.image.height && w<disparity_image.image.width);
00097 float val;
00098 memcpy(&val, &(disparity_image.image.data.at( h*disparity_image.image.step + sizeof(float)*w )), sizeof(float));
00099 if (std::isnan(val) || std::isinf(val)) return false;
00100 if (val <=0 || val < disparity_image.min_disparity || val > disparity_image.max_disparity) return false;
00101 return true;
00102 }
00103
00106 inline void projectTo3d(float u, float v, float disparity,
00107 const stereo_msgs::DisparityImage &disparity_image,
00108 const sensor_msgs::CameraInfo &camera_info,
00109 float &x, float &y, float &z)
00110 {
00111 float fx = camera_info.P[0*4+0];
00112 float fy = camera_info.P[1*4+1];
00113 float cx = camera_info.P[0*4+2];
00114 float cy = camera_info.P[1*4+2];
00115
00116 z = (disparity_image.f * disparity_image.T) / disparity;
00117 x = (u - cx) * z / fx;
00118 y = (v - cy) * z / fy;
00119 }
00120
00122 inline void getPoint(const stereo_msgs::DisparityImage &disparity_image,
00123 const sensor_msgs::CameraInfo &camera_info,
00124 unsigned int h, unsigned int w,
00125 float &x, float &y, float &z)
00126 {
00127 ROS_ASSERT(hasDisparityValue(disparity_image, h, w));
00128 float disparity;
00129 getValue(disparity_image.image, h, w, disparity);
00130 projectTo3d(w, h, disparity, disparity_image, camera_info, x, y, z);
00131 }
00132
00133 }
00134
00135
00136 #endif