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
00031
00032
00033
00034
00035 #define BOOST_PARAMETER_MAX_ARITY 7
00036 #include "simple_occupancy_grid_array_display.h"
00037 #include <Eigen/Geometry>
00038 #include <jsk_recognition_utils/pcl_conversion_util.h>
00039 #include <jsk_topic_tools/color_utils.h>
00040 #include "rviz_util.h"
00041 #include <jsk_recognition_utils/geo/plane.h>
00042
00043 namespace jsk_rviz_plugins
00044 {
00045 SimpleOccupancyGridArrayDisplay::SimpleOccupancyGridArrayDisplay()
00046 {
00047 auto_color_property_ = new rviz::BoolProperty(
00048 "Auto Color", true,
00049 "Auto coloring",
00050 this, SLOT(updateAutoColor()));
00051
00052 alpha_property_ = new rviz::FloatProperty(
00053 "Alpha", 1.0,
00054 "Amount of transparency to apply to the polygon.",
00055 this, SLOT(updateAlpha()));
00056
00057 alpha_property_->setMin(0.0);
00058 alpha_property_->setMax(1.0);
00059
00060
00061 }
00062
00063 SimpleOccupancyGridArrayDisplay::~SimpleOccupancyGridArrayDisplay()
00064 {
00065 delete alpha_property_;
00066 allocateCloudsAndNodes(0);
00067 }
00068
00069 void SimpleOccupancyGridArrayDisplay::onInitialize()
00070 {
00071 MFDClass::onInitialize();
00072 updateAlpha();
00073 updateAutoColor();
00074 }
00075
00076 void SimpleOccupancyGridArrayDisplay::allocateCloudsAndNodes(const size_t num)
00077 {
00078 if (num > clouds_.size()) {
00079 for (size_t i = clouds_.size(); i < num; i++) {
00080 Ogre::SceneNode* node = scene_node_->createChildSceneNode();
00081 rviz::PointCloud* cloud = new rviz::PointCloud();
00082 cloud->setRenderMode(rviz::PointCloud::RM_TILES);
00083 cloud->setCommonDirection( Ogre::Vector3::UNIT_Z );
00084 cloud->setCommonUpVector( Ogre::Vector3::UNIT_Y );
00085 node->attachObject(cloud);
00086 clouds_.push_back(cloud);
00087 nodes_.push_back(node);
00088 }
00089 }
00090 else if (num < clouds_.size())
00091 {
00092 for (size_t i = num; i < clouds_.size(); i++) {
00093 nodes_[i]->detachObject(clouds_[i]);
00094 delete clouds_[i];
00095 scene_manager_->destroySceneNode(nodes_[i]);
00096 }
00097 clouds_.resize(num);
00098 nodes_.resize(num);
00099 }
00100 }
00101
00102 void SimpleOccupancyGridArrayDisplay::reset()
00103 {
00104 MFDClass::reset();
00105 allocateCloudsAndNodes(0);
00106 }
00107
00108 void SimpleOccupancyGridArrayDisplay::processMessage(
00109 const jsk_recognition_msgs::SimpleOccupancyGridArray::ConstPtr& msg)
00110 {
00111 Ogre::ColourValue white(1, 1, 1, 1);
00112 allocateCloudsAndNodes(msg->grids.size());
00113 for (size_t i = 0; i < msg->grids.size(); i++) {
00114 Ogre::SceneNode* node = nodes_[i];
00115 rviz::PointCloud* cloud = clouds_[i];
00116 const jsk_recognition_msgs::SimpleOccupancyGrid grid = msg->grids[i];
00117 Ogre::Vector3 position;
00118 Ogre::Quaternion quaternion;
00119
00120
00121 geometry_msgs::Pose plane_pose;
00122 jsk_recognition_utils::Plane::Ptr plane(new jsk_recognition_utils::Plane(grid.coefficients));
00123 Eigen::Affine3f plane_pose_eigen = plane->coordinates();
00124 tf::poseEigenToMsg(plane_pose_eigen, plane_pose);
00125 if(!context_->getFrameManager()->transform(grid.header, plane_pose,
00126 position,
00127 quaternion)) {
00128 std::ostringstream oss;
00129 oss << "Error transforming pose";
00130 oss << " from frame '" << grid.header.frame_id << "'";
00131 oss << " to frame '" << qPrintable(fixed_frame_) << "'";
00132 ROS_ERROR_STREAM(oss.str());
00133 setStatus(rviz::StatusProperty::Error, "Transform", QString::fromStdString(oss.str()));
00134 return;
00135 }
00136 node->setPosition(position);
00137 node->setOrientation(quaternion);
00138 cloud->setDimensions(grid.resolution, grid.resolution, 0.0);
00139 std::vector<rviz::PointCloud::Point> points;
00140 for (size_t ci = 0; ci < grid.cells.size(); ci++) {
00141 const geometry_msgs::Point p = grid.cells[ci];
00142 rviz::PointCloud::Point point;
00143 if (auto_color_) {
00144 point.color = rviz::colorMsgToOgre(jsk_topic_tools::colorCategory20(i));
00145 }
00146 else {
00147 point.color = white;
00148 }
00149 point.position.x = p.x;
00150 point.position.y = p.y;
00151 point.position.z = p.z;
00152 points.push_back(point);
00153 }
00154 cloud->clear();
00155 cloud->setAlpha(alpha_);
00156 if (!points.empty()) {
00157 cloud->addPoints(&points.front(), points.size());
00158 }
00159 }
00160 context_->queueRender();
00161 }
00162
00163 void SimpleOccupancyGridArrayDisplay::updateAlpha()
00164 {
00165 alpha_ = alpha_property_->getFloat();
00166 }
00167
00168 void SimpleOccupancyGridArrayDisplay::updateAutoColor()
00169 {
00170 auto_color_ = auto_color_property_->getBool();
00171 }
00172
00173 }
00174
00175 #include <pluginlib/class_list_macros.h>
00176 PLUGINLIB_EXPORT_CLASS( jsk_rviz_plugins::SimpleOccupancyGridArrayDisplay, rviz::Display )
00177