$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 #include "robot_model_display.h" 00031 #include "rviz/visualization_manager.h" 00032 #include "rviz/robot/robot.h" 00033 #include "rviz/robot/tf_link_updater.h" 00034 #include "rviz/properties/property.h" 00035 #include "rviz/properties/property_manager.h" 00036 00037 #include <urdf/model.h> 00038 00039 #include <OGRE/OgreSceneNode.h> 00040 #include <OGRE/OgreSceneManager.h> 00041 00042 #include <tf/transform_listener.h> 00043 00044 namespace rviz 00045 { 00046 00047 void linkUpdaterStatusFunction(StatusLevel level, const std::string& link_name, const std::string& text, RobotModelDisplay* display) 00048 { 00049 display->setStatus(level, link_name, text); 00050 } 00051 00052 RobotModelDisplay::RobotModelDisplay( const std::string& name, VisualizationManager* manager ) 00053 : Display( name, manager ) 00054 , description_param_("robot_description") 00055 , has_new_transforms_( false ) 00056 , time_since_last_transform_( 0.0f ) 00057 , update_rate_( 0.0f ) 00058 { 00059 robot_ = new Robot( vis_manager_, "Robot: " + name_ ); 00060 00061 setVisualVisible( true ); 00062 setCollisionVisible( false ); 00063 00064 setAlpha(1.0f); 00065 } 00066 00067 RobotModelDisplay::~RobotModelDisplay() 00068 { 00069 delete robot_; 00070 } 00071 00072 void RobotModelDisplay::setAlpha( float alpha ) 00073 { 00074 alpha_ = alpha; 00075 00076 robot_->setAlpha(alpha_); 00077 00078 propertyChanged(alpha_property_); 00079 } 00080 00081 void RobotModelDisplay::setRobotDescription( const std::string& description_param ) 00082 { 00083 description_param_ = description_param; 00084 00085 propertyChanged(robot_description_property_); 00086 00087 if ( isEnabled() ) 00088 { 00089 load(); 00090 causeRender(); 00091 } 00092 } 00093 00094 void RobotModelDisplay::setVisualVisible( bool visible ) 00095 { 00096 robot_->setVisualVisible( visible ); 00097 00098 propertyChanged(visual_enabled_property_); 00099 00100 causeRender(); 00101 } 00102 00103 void RobotModelDisplay::setCollisionVisible( bool visible ) 00104 { 00105 robot_->setCollisionVisible( visible ); 00106 00107 propertyChanged(collision_enabled_property_); 00108 00109 causeRender(); 00110 } 00111 00112 void RobotModelDisplay::setUpdateRate( float rate ) 00113 { 00114 update_rate_ = rate; 00115 00116 propertyChanged(update_rate_property_); 00117 00118 causeRender(); 00119 } 00120 00121 void RobotModelDisplay::setTFPrefix(const std::string& prefix) 00122 { 00123 tf_prefix_ = prefix; 00124 00125 propertyChanged(tf_prefix_property_); 00126 00127 causeRender(); 00128 } 00129 00130 bool RobotModelDisplay::isVisualVisible() 00131 { 00132 return robot_->isVisualVisible(); 00133 } 00134 00135 bool RobotModelDisplay::isCollisionVisible() 00136 { 00137 return robot_->isCollisionVisible(); 00138 } 00139 00140 void RobotModelDisplay::load() 00141 { 00142 std::string content; 00143 if (!update_nh_.getParam(description_param_, content)) 00144 { 00145 std::string loc; 00146 if (update_nh_.searchParam(description_param_, loc)) 00147 { 00148 update_nh_.getParam(loc, content); 00149 } 00150 else 00151 { 00152 clear(); 00153 00154 std::stringstream ss; 00155 ss << "Parameter [" << description_param_ << "] does not exist, and was not found by searchParam()"; 00156 setStatus(status_levels::Error, "URDF", ss.str()); 00157 return; 00158 } 00159 } 00160 00161 if (content.empty()) 00162 { 00163 clear(); 00164 setStatus(status_levels::Error, "URDF", "URDF is empty"); 00165 return; 00166 } 00167 00168 if ( content == robot_description_ ) 00169 { 00170 return; 00171 } 00172 00173 robot_description_ = content; 00174 00175 TiXmlDocument doc; 00176 doc.Parse(robot_description_.c_str()); 00177 if (!doc.RootElement()) 00178 { 00179 clear(); 00180 setStatus(status_levels::Error, "URDF", "URDF failed XML parse"); 00181 return; 00182 } 00183 00184 urdf::Model descr; 00185 if (!descr.initXml(doc.RootElement())) 00186 { 00187 clear(); 00188 setStatus(status_levels::Error, "URDF", "URDF failed Model parse"); 00189 return; 00190 } 00191 00192 setStatus(status_levels::Ok, "URDF", "URDF parsed OK"); 00193 robot_->load( doc.RootElement(), descr ); 00194 robot_->update( TFLinkUpdater(vis_manager_->getFrameManager(), boost::bind(linkUpdaterStatusFunction, _1, _2, _3, this), tf_prefix_) ); 00195 } 00196 00197 void RobotModelDisplay::onEnable() 00198 { 00199 load(); 00200 robot_->setVisible( true ); 00201 } 00202 00203 void RobotModelDisplay::onDisable() 00204 { 00205 robot_->setVisible( false ); 00206 clear(); 00207 } 00208 00209 void RobotModelDisplay::update(float wall_dt, float ros_dt) 00210 { 00211 time_since_last_transform_ += wall_dt; 00212 00213 bool update = update_rate_ < 0.0001f || time_since_last_transform_ >= update_rate_; 00214 00215 if ( has_new_transforms_ || update ) 00216 { 00217 robot_->update(TFLinkUpdater(vis_manager_->getFrameManager(), boost::bind(linkUpdaterStatusFunction, _1, _2, _3, this), tf_prefix_)); 00218 causeRender(); 00219 00220 has_new_transforms_ = false; 00221 time_since_last_transform_ = 0.0f; 00222 } 00223 } 00224 00225 void RobotModelDisplay::targetFrameChanged() 00226 { 00227 has_new_transforms_ = true; 00228 } 00229 00230 void RobotModelDisplay::createProperties() 00231 { 00232 visual_enabled_property_ = property_manager_->createProperty<BoolProperty>( "Visual Enabled", property_prefix_, boost::bind( &RobotModelDisplay::isVisualVisible, this ), 00233 boost::bind( &RobotModelDisplay::setVisualVisible, this, _1 ), parent_category_, this ); 00234 setPropertyHelpText(visual_enabled_property_, "Whether to display the visual representation of the robot."); 00235 collision_enabled_property_ = property_manager_->createProperty<BoolProperty>( "Collision Enabled", property_prefix_, boost::bind( &RobotModelDisplay::isCollisionVisible, this ), 00236 boost::bind( &RobotModelDisplay::setCollisionVisible, this, _1 ), parent_category_, this ); 00237 setPropertyHelpText(collision_enabled_property_, "Whether to display the collision representation of the robot."); 00238 update_rate_property_ = property_manager_->createProperty<FloatProperty>( "Update Interval", property_prefix_, boost::bind( &RobotModelDisplay::getUpdateRate, this ), 00239 boost::bind( &RobotModelDisplay::setUpdateRate, this, _1 ), parent_category_, this ); 00240 setPropertyHelpText(update_rate_property_, "Interval at which to update the links, in seconds. 0 means to update every update cycle."); 00241 FloatPropertyPtr float_prop = update_rate_property_.lock(); 00242 float_prop->setMin( 0.0 ); 00243 float_prop->addLegacyName("Update Rate"); 00244 00245 alpha_property_ = property_manager_->createProperty<FloatProperty>( "Alpha", property_prefix_, boost::bind( &RobotModelDisplay::getAlpha, this ), 00246 boost::bind( &RobotModelDisplay::setAlpha, this, _1 ), parent_category_, this ); 00247 setPropertyHelpText(alpha_property_, "Amount of transparency to apply to the links."); 00248 float_prop = alpha_property_.lock(); 00249 float_prop->setMin( 0.0 ); 00250 float_prop->setMax( 1.0 ); 00251 00252 robot_description_property_ = property_manager_->createProperty<StringProperty>( "Robot Description", property_prefix_, boost::bind( &RobotModelDisplay::getRobotDescription, this ), 00253 boost::bind( &RobotModelDisplay::setRobotDescription, this, _1 ), parent_category_, this ); 00254 setPropertyHelpText(robot_description_property_, "Name of the parameter to search for to load the robot description."); 00255 00256 tf_prefix_property_ = property_manager_->createProperty<StringProperty>( "TF Prefix", property_prefix_, boost::bind( &RobotModelDisplay::getTFPrefix, this ), 00257 boost::bind( &RobotModelDisplay::setTFPrefix, this, _1 ), parent_category_, this ); 00258 setPropertyHelpText(tf_prefix_property_, "Robot Model normally assumes the link name is the same as the tf frame name. This option allows you to set a prefix. Mainly useful for multi-robot situations."); 00259 00260 robot_->setPropertyManager( property_manager_, parent_category_ ); 00261 } 00262 00263 void RobotModelDisplay::clear() 00264 { 00265 robot_->clear(); 00266 clearStatuses(); 00267 robot_description_.clear(); 00268 } 00269 00270 void RobotModelDisplay::reset() 00271 { 00272 Display::reset(); 00273 has_new_transforms_ = true; 00274 } 00275 00276 } // namespace rviz 00277