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