$search
00001 /* 00002 * Copyright (c) 2008, 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 * 00030 */ 00031 00032 #include "collision_map_display.h" 00033 #include "rviz/visualization_manager.h" 00034 #include "rviz/properties/property.h" 00035 #include "rviz/properties/property_manager.h" 00036 #include "rviz/common.h" 00037 00038 #include <tf/transform_listener.h> 00039 00040 #include <boost/bind.hpp> 00041 00042 #include <OGRE/OgreSceneNode.h> 00043 #include <OGRE/OgreSceneManager.h> 00044 #include <OGRE/OgreManualObject.h> 00045 #include <OGRE/OgreBillboardSet.h> 00046 00047 #include <ogre_tools/point_cloud.h> 00048 00049 namespace mapping_rviz_plugin 00050 { 00051 00052 CollisionMapDisplay::CollisionMapDisplay(const std::string & name, rviz::VisualizationManager * manager) 00053 : Display(name, manager) 00054 , color_(0.1f, 1.0f, 0.0f) 00055 , render_operation_(collision_render_ops::CBoxes) 00056 , override_color_(false) 00057 , tf_filter_(*manager->getTFClient(), "", 2, update_nh_) 00058 { 00059 scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode(); 00060 00061 static int count = 0; 00062 std::stringstream ss; 00063 ss << "Collision Map" << count++; 00064 manual_object_ = scene_manager_->createManualObject(ss.str()); 00065 manual_object_->setDynamic(true); 00066 scene_node_->attachObject(manual_object_); 00067 00068 cloud_ = new ogre_tools::PointCloud(); 00069 setAlpha(1.0f); 00070 setPointSize(0.05f); 00071 scene_node_->attachObject(cloud_); 00072 00073 tf_filter_.connectInput(sub_); 00074 tf_filter_.registerCallback(boost::bind(&CollisionMapDisplay::incomingMessage, this, _1)); 00075 } 00076 00077 CollisionMapDisplay::~CollisionMapDisplay() 00078 { 00079 unsubscribe(); 00080 clear(); 00081 00082 scene_manager_->destroyManualObject(manual_object_); 00083 00084 delete cloud_; 00085 } 00086 00087 void CollisionMapDisplay::clear() 00088 { 00089 manual_object_->clear(); 00090 cloud_->clear(); 00091 } 00092 00093 void CollisionMapDisplay::setTopic(const std::string & topic) 00094 { 00095 unsubscribe(); 00096 topic_ = topic; 00097 subscribe(); 00098 00099 propertyChanged(topic_property_); 00100 00101 causeRender(); 00102 } 00103 00104 void CollisionMapDisplay::setColor(const rviz::Color & color) 00105 { 00106 color_ = color; 00107 00108 propertyChanged(color_property_); 00109 processMessage(current_message_); 00110 causeRender(); 00111 } 00112 00113 void CollisionMapDisplay::setOverrideColor(bool override) 00114 { 00115 override_color_ = override; 00116 00117 propertyChanged(override_color_property_); 00118 00119 processMessage(current_message_); 00120 causeRender(); 00121 } 00122 00123 void CollisionMapDisplay::setRenderOperation(int op) 00124 { 00125 render_operation_ = op; 00126 00127 propertyChanged(render_operation_property_); 00128 00129 processMessage(current_message_); 00130 causeRender(); 00131 } 00132 00133 void CollisionMapDisplay::setPointSize(float size) 00134 { 00135 point_size_ = size; 00136 00137 propertyChanged(point_size_property_); 00138 00139 cloud_->setDimensions(size, size, size); 00140 causeRender(); 00141 } 00142 00143 void CollisionMapDisplay::setAlpha(float alpha) 00144 { 00145 alpha_ = alpha; 00146 cloud_->setAlpha(alpha); 00147 00148 propertyChanged(alpha_property_); 00149 00150 processMessage(current_message_); 00151 causeRender(); 00152 } 00153 00154 void CollisionMapDisplay::subscribe() 00155 { 00156 if (!isEnabled()) 00157 return; 00158 00159 if (!topic_.empty()) 00160 { 00161 sub_.subscribe(update_nh_, topic_, 1); 00162 } 00163 } 00164 00165 void CollisionMapDisplay::unsubscribe() 00166 { 00167 sub_.unsubscribe(); 00168 } 00169 00170 void CollisionMapDisplay::onEnable() 00171 { 00172 scene_node_->setVisible(true); 00173 subscribe(); 00174 } 00175 00176 void CollisionMapDisplay::onDisable() 00177 { 00178 unsubscribe(); 00179 clear(); 00180 scene_node_->setVisible(false); 00181 } 00182 00183 void CollisionMapDisplay::fixedFrameChanged() 00184 { 00185 tf_filter_.setTargetFrame(fixed_frame_); 00186 clear(); 00187 } 00188 00189 void CollisionMapDisplay::update(float wall_dt, float ros_dt) 00190 { 00191 } 00192 00193 void CollisionMapDisplay::processMessage(const arm_navigation_msgs::CollisionMap::ConstPtr& msg) 00194 { 00195 clear(); 00196 00197 if (!msg) 00198 { 00199 return; 00200 } 00201 00202 tf::Stamped<tf::Pose> pose(btTransform(btQuaternion(0.0f, 0.0f, 0.0f), 00203 btVector3(0.0f, 0.0f, 0.0f)), msg->header.stamp, 00204 msg->header.frame_id); 00205 00206 try 00207 { 00208 vis_manager_->getTFClient()->transformPose(fixed_frame_, pose, pose); 00209 } 00210 catch (tf::TransformException & e) 00211 { 00212 ROS_ERROR("Error transforming from frame 'map' to frame '%s'", 00213 fixed_frame_.c_str()); 00214 } 00215 00216 Ogre::Vector3 position = Ogre::Vector3(pose.getOrigin().x(), 00217 pose.getOrigin().y(), pose.getOrigin().z()); 00218 rviz::robotToOgre(position); 00219 00220 btScalar yaw, pitch, roll; 00221 pose.getBasis().getEulerZYX(yaw, pitch, roll); 00222 00223 Ogre::Matrix3 orientation(rviz::ogreMatrixFromRobotEulers(yaw, pitch, roll)); 00224 00225 manual_object_->clear(); 00226 00227 Ogre::ColourValue color; 00228 00229 uint32_t num_boxes = msg->get_boxes_size(); 00230 ROS_DEBUG("Collision map contains %d boxes.", num_boxes); 00231 00232 // If we render points, we don't care about the order 00233 if (render_operation_ == collision_render_ops::CPoints) 00234 { 00235 typedef std::vector<ogre_tools::PointCloud::Point> V_Point; 00236 V_Point points; 00237 if (num_boxes > 0) 00238 { 00239 points.resize(num_boxes); 00240 for (uint32_t i = 0; i < num_boxes; i++) 00241 { 00242 ogre_tools::PointCloud::Point & current_point = points[i]; 00243 00244 current_point.x = msg->boxes[i].center.x; 00245 current_point.y = msg->boxes[i].center.y; 00246 current_point.z = msg->boxes[i].center.z; 00247 color = Ogre::ColourValue(color_.r_, color_.g_, color_.b_, alpha_); 00248 current_point.setColor(color.r, color.g, color.b); 00249 } 00250 } 00251 cloud_->clear(); 00252 00253 if (!points.empty()) 00254 { 00255 cloud_->addPoints(&points.front(), points.size()); 00256 } 00257 } 00258 else 00259 { 00260 geometry_msgs::Point32 center, extents; 00261 color = Ogre::ColourValue(color_.r_, color_.g_, color_.b_, alpha_); 00262 if (num_boxes > 0) 00263 { 00264 for (uint32_t i = 0; i < num_boxes; i++) 00265 { 00266 manual_object_->estimateVertexCount(8); 00267 manual_object_->begin("BaseWhiteNoLighting", 00268 Ogre::RenderOperation::OT_LINE_STRIP); 00269 center.x = msg->boxes[i].center.x; 00270 center.y = msg->boxes[i].center.y; 00271 center.z = msg->boxes[i].center.z; 00272 extents.x = msg->boxes[i].extents.x; 00273 extents.y = msg->boxes[i].extents.y; 00274 extents.z = msg->boxes[i].extents.z; 00275 00276 manual_object_->position(center.x - extents.x, center.y - extents.y, 00277 center.z - extents.z); 00278 manual_object_->colour(color); 00279 manual_object_->position(center.x - extents.x, center.y + extents.y, 00280 center.z - extents.z); 00281 manual_object_->colour(color); 00282 manual_object_->position(center.x + extents.x, center.y + extents.y, 00283 center.z - extents.z); 00284 manual_object_->colour(color); 00285 manual_object_->position(center.x + extents.x, center.y - extents.y, 00286 center.z - extents.z); 00287 manual_object_->colour(color); 00288 manual_object_->position(center.x + extents.x, center.y - extents.y, 00289 center.z + extents.z); 00290 manual_object_->colour(color); 00291 manual_object_->position(center.x + extents.x, center.y + extents.y, 00292 center.z + extents.z); 00293 manual_object_->colour(color); 00294 manual_object_->position(center.x - extents.x, center.y + extents.y, 00295 center.z + extents.z); 00296 manual_object_->colour(color); 00297 manual_object_->position(center.x - extents.x, center.y - extents.y, 00298 center.z + extents.z); 00299 manual_object_->colour(color); 00300 manual_object_->end(); 00301 } 00302 } 00303 } 00304 00305 scene_node_->setPosition(position); 00306 scene_node_->setOrientation(orientation); 00307 } 00308 00309 void CollisionMapDisplay::incomingMessage(const arm_navigation_msgs::CollisionMap::ConstPtr& message) 00310 { 00311 processMessage(message); 00312 } 00313 00314 void CollisionMapDisplay::reset() 00315 { 00316 clear(); 00317 } 00318 00319 void CollisionMapDisplay::targetFrameChanged() 00320 { 00321 } 00322 00323 void CollisionMapDisplay::createProperties() 00324 { 00325 override_color_property_ = property_manager_->createProperty<rviz::BoolProperty> ("Override Color", property_prefix_, 00326 boost::bind(&CollisionMapDisplay::getOverrideColor, this), 00327 boost::bind(&CollisionMapDisplay::setOverrideColor, this, _1), parent_category_, 00328 this); 00329 color_property_ = property_manager_->createProperty<rviz::ColorProperty> ("Color", property_prefix_, boost::bind(&CollisionMapDisplay::getColor, this), 00330 boost::bind(&CollisionMapDisplay::setColor, this, _1), parent_category_, this); 00331 render_operation_property_ = property_manager_->createProperty<rviz::EnumProperty> ("Render Operation", property_prefix_, 00332 boost::bind(&CollisionMapDisplay::getRenderOperation, this), 00333 boost::bind(&CollisionMapDisplay::setRenderOperation, this, _1), 00334 parent_category_, this); 00335 rviz::EnumPropertyPtr render_prop = render_operation_property_.lock(); 00336 render_prop->addOption("Boxes", collision_render_ops::CBoxes); 00337 render_prop->addOption("Points", collision_render_ops::CPoints); 00338 00339 alpha_property_ = property_manager_->createProperty<rviz::FloatProperty> ("Alpha", property_prefix_, boost::bind(&CollisionMapDisplay::getAlpha, this), 00340 boost::bind(&CollisionMapDisplay::setAlpha, this, _1), parent_category_, this); 00341 topic_property_ = property_manager_->createProperty<rviz::ROSTopicStringProperty> ("Topic", property_prefix_, boost::bind(&CollisionMapDisplay::getTopic, this), 00342 boost::bind(&CollisionMapDisplay::setTopic, this, _1), parent_category_, this); 00343 rviz::ROSTopicStringPropertyPtr topic_prop = topic_property_.lock(); 00344 topic_prop->setMessageType(arm_navigation_msgs::CollisionMap::__s_getDataType()); 00345 } 00346 00347 } // namespace mapping_rviz_plugin