Go to the documentation of this file.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 #include "rviz_interaction_tools/disparity_renderer.h"
00031 #include "rviz_interaction_tools/image_tools.h"
00032
00033 #include <sensor_msgs/image_encodings.h>
00034
00035 #include <OGRE/OgreSceneNode.h>
00036
00037 namespace rviz_interaction_tools
00038 {
00039
00040 DisparityRenderer::DisparityRenderer( Ogre::SceneNode* scene_root, unsigned char render_queue_group ) :
00041 scene_root_(scene_root),
00042 new_point_cloud_(0)
00043 {
00044 image_point_cloud_.setRenderQueueGroup(render_queue_group);
00045 scene_root_->attachObject(&image_point_cloud_);
00046 }
00047
00048 DisparityRenderer::~DisparityRenderer()
00049 {
00050 scene_root_->detachObject(&image_point_cloud_);
00051 }
00052
00053 bool DisparityRenderer::setDisparityImage(
00054 const stereo_msgs::DisparityImage &disparity_image,
00055 const sensor_msgs::CameraInfo &camera_info, const sensor_msgs::Image *image )
00056 {
00057 boost::mutex::scoped_lock(mutex_);
00058
00059
00060
00061 raw_points_.clear();
00062 raw_points_.reserve(disparity_image.image.width
00063 * disparity_image.image.height);
00064
00065 rviz_interaction_tools::PointCloud::Point point;
00066 point.setColor(1, 1, 1);
00067
00068 for (unsigned int i = 0; i < disparity_image.image.height; i++)
00069 {
00070 for (unsigned int j = 0; j < disparity_image.image.width; j++)
00071 {
00072 if (rviz_interaction_tools::hasDisparityValue(disparity_image, i, j))
00073 {
00074
00075 rviz_interaction_tools::getPoint(disparity_image, camera_info, i, j,
00076 point.x, point.y, point.z);
00077 if (std::isnan(point.x) || std::isinf(point.x))
00078 continue;
00079 if (std::isnan(point.y) || std::isinf(point.y))
00080 continue;
00081 if (std::isnan(point.z) || std::isinf(point.z))
00082 continue;
00083
00084 if (point.x < -50 || point.x > 50)
00085 ROS_INFO("Point x: %f", point.x);
00086 if (point.y < -50 || point.y > 50)
00087 ROS_INFO("Point x: %f", point.y);
00088 if (point.z < -50 || point.z > 50)
00089 ROS_INFO("Point x: %f", point.z);
00090
00091 if (image)
00092 {
00093 if (image->encoding == sensor_msgs::image_encodings::MONO8)
00094 {
00095 float l = float(image->data[i * image->step + j]) / 255.0;
00096 point.setColor(l, l, l);
00097 }
00098 else if (image->encoding == sensor_msgs::image_encodings::BGR8)
00099 {
00100 float b = float(image->data[i * image->step + j*3]) / 255.0;
00101 float g = float(image->data[i * image->step + j*3 + 1]) / 255.0;
00102 float r = float(image->data[i * image->step + j*3 + 2]) / 255.0;
00103 point.setColor(r, g, b);
00104 }
00105 else if (image->encoding == sensor_msgs::image_encodings::RGB8)
00106 {
00107 float r = float(image->data[i * image->step + j*3]) / 255.0;
00108 float g = float(image->data[i * image->step + j*3 + 1]) / 255.0;
00109 float b = float(image->data[i * image->step + j*3 + 2]) / 255.0;
00110 point.setColor(r, g, b);
00111 }
00112 else
00113 {
00114 point.setColor(1,1,1);
00115 }
00116 }
00117
00118 raw_points_.push_back(point);
00119 }
00120 }
00121 }
00122
00123 new_point_cloud_ = true;
00124 return true;
00125 }
00126
00127 bool DisparityRenderer::update()
00128 {
00129 boost::mutex::scoped_lock(mutex_);
00130
00131 if (!new_point_cloud_)
00132 {
00133 return false;
00134 }
00135
00136 image_point_cloud_.clear();
00137 image_point_cloud_.addPoints(&raw_points_[0], raw_points_.size());
00138
00139 Ogre::Vector3 min = image_point_cloud_.getBoundingBox().getMinimum();
00140 Ogre::Vector3 max = image_point_cloud_.getBoundingBox().getMaximum();
00141 ROS_DEBUG("Bbox min: %f %f %f max: %f %f %f # of points: %d",
00142 min.x, min.y, min.z, max.x, max.y, max.z, (int)raw_points_.size() );
00143
00144 return true;
00145 }
00146
00147 void DisparityRenderer::clear()
00148 {
00149 boost::mutex::scoped_lock(mutex_);
00150 image_point_cloud_.clear();
00151 }
00152
00153 }