robot_model_display.cpp
Go to the documentation of this file.
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 <OGRE/OgreSceneNode.h>
00031 #include <OGRE/OgreSceneManager.h>
00032 
00033 #include <urdf/model.h>
00034 
00035 #include <tf/transform_listener.h>
00036 
00037 #include "rviz/display_context.h"
00038 #include "rviz/robot/robot.h"
00039 #include "rviz/robot/tf_link_updater.h"
00040 #include "rviz/properties/float_property.h"
00041 #include "rviz/properties/property.h"
00042 #include "rviz/properties/string_property.h"
00043 
00044 #include "robot_model_display.h"
00045 
00046 namespace rviz
00047 {
00048 
00049 void linkUpdaterStatusFunction( StatusProperty::Level level,
00050                                 const std::string& link_name,
00051                                 const std::string& text,
00052                                 RobotModelDisplay* display )
00053 {
00054   display->setStatus( level, QString::fromStdString( link_name ), QString::fromStdString( text ));
00055 }
00056 
00057 RobotModelDisplay::RobotModelDisplay()
00058   : Display()
00059   , has_new_transforms_( false )
00060   , time_since_last_transform_( 0.0f )
00061 {
00062   visual_enabled_property_ = new Property( "Visual Enabled", true,
00063                                            "Whether to display the visual representation of the robot.",
00064                                            this, SLOT( updateVisualVisible() ));
00065 
00066   collision_enabled_property_ = new Property( "Collision Enabled", false,
00067                                               "Whether to display the collision representation of the robot.",
00068                                               this, SLOT( updateCollisionVisible() ));
00069 
00070   update_rate_property_ = new FloatProperty( "Update Interval", 0,
00071                                              "Interval at which to update the links, in seconds. "
00072                                              " 0 means to update every update cycle.",
00073                                              this );
00074   update_rate_property_->setMin( 0 );
00075 
00076   alpha_property_ = new FloatProperty( "Alpha", 1,
00077                                        "Amount of transparency to apply to the links.",
00078                                        this, SLOT( updateAlpha() ));
00079   alpha_property_->setMin( 0.0 );
00080   alpha_property_->setMax( 1.0 );
00081 
00082   robot_description_property_ = new StringProperty( "Robot Description", "robot_description",
00083                                                     "Name of the parameter to search for to load the robot description.",
00084                                                     this, SLOT( updateRobotDescription() ));
00085 
00086   tf_prefix_property_ = new StringProperty( "TF Prefix", "",
00087                                             "Robot Model normally assumes the link name is the same as the tf frame name. "
00088                                             " This option allows you to set a prefix.  Mainly useful for multi-robot situations.",
00089                                             this, SLOT( updateTfPrefix() ));
00090 }
00091 
00092 RobotModelDisplay::~RobotModelDisplay()
00093 {
00094   delete robot_;
00095 }
00096 
00097 void RobotModelDisplay::onInitialize()
00098 {
00099   robot_ = new Robot( scene_node_, context_, "Robot: " + getName().toStdString(), this );
00100 
00101   updateVisualVisible();
00102   updateCollisionVisible();
00103   updateAlpha();
00104 }
00105 
00106 void RobotModelDisplay::updateAlpha()
00107 {
00108   robot_->setAlpha( alpha_property_->getFloat() );
00109   context_->queueRender();
00110 }
00111 
00112 void RobotModelDisplay::updateRobotDescription()
00113 {
00114   if( isEnabled() )
00115   {
00116     load();
00117     context_->queueRender();
00118   }
00119 }
00120 
00121 void RobotModelDisplay::updateVisualVisible()
00122 {
00123   robot_->setVisualVisible( visual_enabled_property_->getValue().toBool() );
00124   context_->queueRender();
00125 }
00126 
00127 void RobotModelDisplay::updateCollisionVisible()
00128 {
00129   robot_->setCollisionVisible( collision_enabled_property_->getValue().toBool() );
00130   context_->queueRender();
00131 }
00132 
00133 void RobotModelDisplay::updateTfPrefix()
00134 {
00135   clearStatuses();
00136   context_->queueRender();
00137 }
00138 
00139 void RobotModelDisplay::load()
00140 {
00141   std::string content;
00142   if( !update_nh_.getParam( robot_description_property_->getStdString(), content ))
00143   {
00144     std::string loc;
00145     if( update_nh_.searchParam( robot_description_property_->getStdString(), loc ))
00146     {
00147       update_nh_.getParam( loc, content );
00148     }
00149     else
00150     {
00151       clear();
00152       setStatus( StatusProperty::Error, "URDF",
00153                  "Parameter [" + robot_description_property_->getString()
00154                  + "] does not exist, and was not found by searchParam()" );
00155       return;
00156     }
00157   }
00158 
00159   if( content.empty() )
00160   {
00161     clear();
00162     setStatus( StatusProperty::Error, "URDF", "URDF is empty" );
00163     return;
00164   }
00165 
00166   if( content == robot_description_ )
00167   {
00168     return;
00169   }
00170 
00171   robot_description_ = content;
00172 
00173   TiXmlDocument doc;
00174   doc.Parse( robot_description_.c_str() );
00175   if( !doc.RootElement() )
00176   {
00177     clear();
00178     setStatus( StatusProperty::Error, "URDF", "URDF failed XML parse" );
00179     return;
00180   }
00181 
00182   urdf::Model descr;
00183   if( !descr.initXml( doc.RootElement() ))
00184   {
00185     clear();
00186     setStatus( StatusProperty::Error, "URDF", "URDF failed Model parse" );
00187     return;
00188   }
00189 
00190   setStatus( StatusProperty::Ok, "URDF", "URDF parsed OK" );
00191   robot_->load( descr );
00192   robot_->update( TFLinkUpdater( context_->getFrameManager(),
00193                                  boost::bind( linkUpdaterStatusFunction, _1, _2, _3, this ),
00194                                  tf_prefix_property_->getStdString() ));
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   float rate = update_rate_property_->getFloat();
00213   bool update = rate < 0.0001f || time_since_last_transform_ >= rate;
00214 
00215   if( has_new_transforms_ || update )
00216   {
00217     robot_->update( TFLinkUpdater( context_->getFrameManager(),
00218                                    boost::bind( linkUpdaterStatusFunction, _1, _2, _3, this ),
00219                                    tf_prefix_property_->getStdString() ));
00220     context_->queueRender();
00221 
00222     has_new_transforms_ = false;
00223     time_since_last_transform_ = 0.0f;
00224   }
00225 }
00226 
00227 void RobotModelDisplay::fixedFrameChanged()
00228 {
00229   has_new_transforms_ = true;
00230 }
00231 
00232 void RobotModelDisplay::clear()
00233 {
00234   robot_->clear();
00235   clearStatuses();
00236   robot_description_.clear();
00237 }
00238 
00239 void RobotModelDisplay::reset()
00240 {
00241   Display::reset();
00242   has_new_transforms_ = true;
00243 }
00244 
00245 } // namespace rviz
00246 
00247 #include <pluginlib/class_list_macros.h>
00248 PLUGINLIB_EXPORT_CLASS( rviz::RobotModelDisplay, rviz::Display )


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Mon Oct 6 2014 07:26:36