$search
00001 /* 00002 * Copyright (c) 2009, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 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