image_tools.h
Go to the documentation of this file.
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 <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


rviz_interaction_tools
Author(s): David Gossow
autogenerated on Mon Oct 6 2014 03:03:25