robot.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 "robot.h"
00031 #include "robot_link.h"
00032 #include "properties/property.h"
00033 #include "properties/property_manager.h"
00034 #include "visualization_manager.h"
00035 
00036 #include "ogre_helpers/object.h"
00037 #include "ogre_helpers/shape.h"
00038 #include "ogre_helpers/axes.h"
00039 
00040 #include <urdf/model.h>
00041 
00042 #include <OGRE/OgreSceneNode.h>
00043 #include <OGRE/OgreSceneManager.h>
00044 #include <OGRE/OgreEntity.h>
00045 #include <OGRE/OgreMaterialManager.h>
00046 #include <OGRE/OgreMaterial.h>
00047 #include <OGRE/OgreResourceGroupManager.h>
00048 
00049 #include <ros/console.h>
00050 
00051 namespace rviz
00052 {
00053 
00054 Robot::Robot( VisualizationManager* manager, const std::string& name )
00055 : scene_manager_(manager->getSceneManager())
00056 , visual_visible_( true )
00057 , collision_visible_( false )
00058 , vis_manager_(manager)
00059 , property_manager_(NULL)
00060 , name_( name )
00061 {
00062   root_visual_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00063   root_collision_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00064   root_other_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00065 
00066   setVisualVisible( visual_visible_ );
00067   setCollisionVisible( collision_visible_ );
00068   setAlpha(1.0f);
00069 }
00070 
00071 Robot::~Robot()
00072 {
00073   clear();
00074 
00075   scene_manager_->destroySceneNode( root_visual_node_->getName() );
00076   scene_manager_->destroySceneNode( root_collision_node_->getName() );
00077   scene_manager_->destroySceneNode( root_other_node_->getName() );
00078 }
00079 
00080 void Robot::setVisible( bool visible )
00081 {
00082   if ( visible )
00083   {
00084     root_visual_node_->setVisible( visual_visible_ );
00085     root_collision_node_->setVisible( collision_visible_ );
00086   }
00087   else
00088   {
00089     root_visual_node_->setVisible( false );
00090     root_collision_node_->setVisible( false );
00091   }
00092 }
00093 
00094 void Robot::setVisualVisible( bool visible )
00095 {
00096   visual_visible_ = visible;
00097   updateLinkVisibilities();
00098 }
00099 
00100 void Robot::setCollisionVisible( bool visible )
00101 {
00102   collision_visible_ = visible;
00103   updateLinkVisibilities();
00104 }
00105 
00106 void Robot::updateLinkVisibilities()
00107 {
00108   M_NameToLink::iterator it = links_.begin();
00109   M_NameToLink::iterator end = links_.end();
00110   for ( ; it != end; ++it )
00111   {
00112     RobotLink* link = it->second;
00113     link->updateVisibility();
00114   }
00115 }
00116 
00117 bool Robot::isVisualVisible()
00118 {
00119   return visual_visible_;
00120 }
00121 
00122 bool Robot::isCollisionVisible()
00123 {
00124   return collision_visible_;
00125 }
00126 
00127 void Robot::setAlpha(float a)
00128 {
00129   alpha_ = a;
00130 
00131   M_NameToLink::iterator it = links_.begin();
00132   M_NameToLink::iterator end = links_.end();
00133   for ( ; it != end; ++it )
00134   {
00135     RobotLink* info = it->second;
00136 
00137     info->setAlpha(alpha_);
00138   }
00139 }
00140 
00141 void Robot::clear()
00142 {
00143   if ( property_manager_ )
00144   {
00145     property_manager_->deleteByUserData( this );
00146   }
00147 
00148   M_NameToLink::iterator link_it = links_.begin();
00149   M_NameToLink::iterator link_end = links_.end();
00150   for ( ; link_it != link_end; ++link_it )
00151   {
00152     RobotLink* info = link_it->second;
00153     delete info;
00154   }
00155 
00156   links_category_.reset();
00157   links_.clear();
00158   root_visual_node_->removeAndDestroyAllChildren();
00159   root_collision_node_->removeAndDestroyAllChildren();
00160   root_other_node_->removeAndDestroyAllChildren();
00161 }
00162 
00163 void Robot::setPropertyManager( PropertyManager* property_manager, const CategoryPropertyWPtr& parent )
00164 {
00165   ROS_ASSERT( property_manager );
00166   ROS_ASSERT( parent.lock() );
00167 
00168   property_manager_ = property_manager;
00169   parent_property_ = parent;
00170 
00171   links_category_ = property_manager_->createCategory( "Links", name_, parent_property_, this );
00172 
00173   if ( !links_.empty() )
00174   {
00175     M_NameToLink::iterator link_it = links_.begin();
00176     M_NameToLink::iterator link_end = links_.end();
00177     for ( ; link_it != link_end; ++link_it )
00178     {
00179       RobotLink* info = link_it->second;
00180 
00181       info->setPropertyManager(property_manager);
00182       info->createProperties();
00183     }
00184   }
00185 
00186   CategoryPropertyPtr cat_prop = links_category_.lock();
00187   cat_prop->collapse();
00188 }
00189 
00190 class LinkComparator
00191 {
00192 public:
00193   bool operator()(const boost::shared_ptr<urdf::Link>& lhs, const boost::shared_ptr<urdf::Link>& rhs)
00194   {
00195     return lhs->name < rhs->name;
00196   }
00197 };
00198 
00199 void Robot::load( TiXmlElement* root_element, urdf::Model &descr, bool visual, bool collision )
00200 {
00201   clear();
00202 
00203   if ( property_manager_ )
00204   {
00205     ROS_ASSERT(!links_category_.lock());
00206     links_category_ = property_manager_->createCategory( "Links", name_, parent_property_, this );
00207   }
00208 
00209   typedef std::vector<boost::shared_ptr<urdf::Link> > V_Link;
00210   V_Link links;
00211   descr.getLinks(links);
00212   std::sort(links.begin(), links.end(), LinkComparator());
00213   V_Link::iterator it = links.begin();
00214   V_Link::iterator end = links.end();
00215   for (; it != end; ++it)
00216   {
00217     const boost::shared_ptr<urdf::Link>& link = *it;
00218 
00219     RobotLink* link_info = new RobotLink(this, vis_manager_);
00220 
00221     if (property_manager_)
00222     {
00223       link_info->setPropertyManager(property_manager_);
00224     }
00225     link_info->load(root_element, descr, link, visual, collision);
00226 
00227     if (!link_info->isValid())
00228     {
00229       delete link_info;
00230       continue;
00231     }
00232 
00233     bool inserted = links_.insert( std::make_pair( link_info->getName(), link_info ) ).second;
00234     ROS_ASSERT( inserted );
00235 
00236     link_info->setAlpha(alpha_);
00237   }
00238 
00239   if (property_manager_)
00240   {
00241     CategoryPropertyPtr cat_prop = links_category_.lock();
00242     cat_prop->collapse();
00243   }
00244 
00245   setVisualVisible(isVisualVisible());
00246   setCollisionVisible(isCollisionVisible());
00247 }
00248 
00249 RobotLink* Robot::getLink( const std::string& name )
00250 {
00251   M_NameToLink::iterator it = links_.find( name );
00252   if ( it == links_.end() )
00253   {
00254     ROS_WARN( "Link [%s] does not exist", name.c_str() );
00255     return NULL;
00256   }
00257 
00258   return it->second;
00259 }
00260 
00261 void Robot::update(const LinkUpdater& updater)
00262 {
00263   M_NameToLink::iterator link_it = links_.begin();
00264   M_NameToLink::iterator link_end = links_.end();
00265   for ( ; link_it != link_end; ++link_it )
00266   {
00267     RobotLink* info = link_it->second;
00268 
00269     info->setToNormalMaterial();
00270 
00271     Ogre::Vector3 visual_position, collision_position;
00272     Ogre::Quaternion visual_orientation, collision_orientation;
00273     bool apply_offset_transforms;
00274     if (updater.getLinkTransforms(info->getName(), visual_position, visual_orientation, collision_position, collision_orientation, apply_offset_transforms))
00275     {
00276       info->setTransforms( visual_position, visual_orientation, collision_position, collision_orientation, apply_offset_transforms );
00277     }
00278     else
00279     {
00280       info->setToErrorMaterial();
00281     }
00282   }
00283 }
00284 
00285 void Robot::setPosition( const Ogre::Vector3& position )
00286 {
00287   root_visual_node_->setPosition( position );
00288   root_collision_node_->setPosition( position );
00289 }
00290 
00291 void Robot::setOrientation( const Ogre::Quaternion& orientation )
00292 {
00293   root_visual_node_->setOrientation( orientation );
00294   root_collision_node_->setOrientation( orientation );
00295 }
00296 
00297 void Robot::setScale( const Ogre::Vector3& scale )
00298 {
00299   root_visual_node_->setScale( scale );
00300   root_collision_node_->setScale( scale );
00301 }
00302 
00303 const Ogre::Vector3& Robot::getPosition()
00304 {
00305   return root_visual_node_->getPosition();
00306 }
00307 
00308 const Ogre::Quaternion& Robot::getOrientation()
00309 {
00310   return root_visual_node_->getOrientation();
00311 }
00312 
00313 } // namespace rviz


rviz
Author(s): Dave Hershberger, Josh Faust
autogenerated on Mon Jan 6 2014 11:54:32