robot.h
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 #ifndef RVIZ_ROBOT_H_
00031 #define RVIZ_ROBOT_H_
00032 
00033 #include "link_updater.h"
00034 
00035 #include <string>
00036 #include <map>
00037 
00038 #include <OgreVector3.h>
00039 #include <OgreQuaternion.h>
00040 #include <OgreAny.h>
00041 
00042 #ifndef Q_MOC_RUN
00043 #include <urdf/model.h> // can be replaced later by urdf_model/types.h
00044 #endif
00045 
00046 namespace Ogre
00047 {
00048 class SceneManager;
00049 class Entity;
00050 class SceneNode;
00051 class Vector3;
00052 class Quaternion;
00053 class Any;
00054 class RibbonTrail;
00055 class SceneNode;
00056 }
00057 
00058 namespace rviz
00059 {
00060 class Object;
00061 class Axes;
00062 }
00063 
00064 namespace tf
00065 {
00066 class TransformListener;
00067 }
00068 
00069 namespace rviz
00070 {
00071 
00072 class Property;
00073 class EnumProperty;
00074 class BoolProperty;
00075 class Robot;
00076 class RobotLink;
00077 class RobotJoint;
00078 class DisplayContext;
00079 
00086 class Robot : public QObject
00087 {
00088 Q_OBJECT
00089 public:
00090   Robot( Ogre::SceneNode* root_node, DisplayContext* context, const std::string& name, Property* parent_property );
00091   virtual ~Robot();
00092 
00100   virtual void load( const urdf::ModelInterface &urdf, bool visual = true, bool collision = true );
00101 
00105   virtual void clear();
00106 
00107   virtual void update(const LinkUpdater& updater);
00108 
00113   virtual void setVisible( bool visible );
00114 
00119   void setVisualVisible( bool visible );
00120 
00125   void setCollisionVisible( bool visible );
00126 
00130   bool isVisible();
00135   bool isVisualVisible();
00140   bool isCollisionVisible();
00141 
00142   void setAlpha(float a);
00143   float getAlpha() { return alpha_; }
00144 
00145   RobotLink* getRootLink() { return root_link_; }
00146   RobotLink* getLink( const std::string& name );
00147   RobotJoint* getJoint( const std::string& name );
00148   
00149   typedef std::map< std::string, RobotLink* > M_NameToLink;
00150   typedef std::map< std::string, RobotJoint* > M_NameToJoint;
00151   const M_NameToLink& getLinks() const { return links_; }
00152   const M_NameToJoint& getJoints() const { return joints_; }
00153 
00154   const std::string& getName() { return name_; }
00155 
00156   Ogre::SceneNode* getVisualNode() { return root_visual_node_; }
00157   Ogre::SceneNode* getCollisionNode() { return root_collision_node_; }
00158   Ogre::SceneNode* getOtherNode() { return root_other_node_; }
00159   Ogre::SceneManager* getSceneManager() { return scene_manager_; }
00160   DisplayContext* getDisplayContext() { return context_; }
00161 
00162   virtual void setPosition( const Ogre::Vector3& position );
00163   virtual void setOrientation( const Ogre::Quaternion& orientation );
00164   virtual void setScale( const Ogre::Vector3& scale );
00165   virtual const Ogre::Vector3& getPosition();
00166   virtual const Ogre::Quaternion& getOrientation();
00167 
00169   class LinkFactory
00170   {
00171   public:
00172     virtual RobotLink* createLink( Robot* robot,
00173                                    const urdf::LinkConstSharedPtr& link,
00174                                    const std::string& parent_joint_name,
00175                                    bool visual,
00176                                    bool collision);
00177     virtual RobotJoint* createJoint( Robot* robot,
00178                                      const urdf::JointConstSharedPtr& joint);
00179   };
00180 
00190   void setLinkFactory(LinkFactory *link_factory);
00191 
00192 
00193   enum LinkTreeStyle {
00194     STYLE_LINK_LIST,         // list of all links sorted by link name
00195     STYLE_DEFAULT = STYLE_LINK_LIST,
00196     STYLE_JOINT_LIST,        // list of joints sorted by joint name
00197     STYLE_LINK_TREE,         // tree of links
00198     STYLE_JOINT_LINK_TREE    // tree of joints with links
00199   };
00200 
00202   void setLinkTreeStyle(LinkTreeStyle style);
00203 
00205   Property *getLinkTreeProperty()
00206   {
00207     return link_tree_;
00208   }
00209 
00210   // set joint checkboxes and All Links Enabled checkbox based on current link enables.
00211   void calculateJointCheckboxes();
00212 
00213 private Q_SLOTS:
00214   void changedLinkTreeStyle();
00215   void changedExpandTree();
00216   void changedHideSubProperties();
00217   void changedEnableAllLinks();
00218   void changedExpandLinkDetails();
00219   void changedExpandJointDetails();
00220 
00221 protected:
00223   void updateLinkVisibilities();
00224 
00227   void unparentLinkProperties();
00228 
00229   // place sub properties under detail (or not)
00230   void useDetailProperty(bool use_detail);
00231 
00233   void addLinkToLinkTree(LinkTreeStyle style, Property *parent, RobotLink *link);
00234   void addJointToLinkTree(LinkTreeStyle style, Property *parent, RobotJoint *joint);
00235 
00236   // set the value of the EnableAllLinks property without affecting child links/joints.
00237   void setEnableAllLinksCheckbox(QVariant val);
00238 
00240   void initLinkTreeStyle();
00241   static bool styleShowLink(LinkTreeStyle style);
00242   static bool styleShowJoint(LinkTreeStyle style);
00243   static bool styleIsTree(LinkTreeStyle style);
00244 
00245   Ogre::SceneManager* scene_manager_;
00246 
00247   M_NameToLink links_;                      
00248   M_NameToJoint joints_;                    
00249   RobotLink *root_link_;
00250 
00251   LinkFactory *link_factory_;               
00252 
00253   Ogre::SceneNode* root_visual_node_;           
00254   Ogre::SceneNode* root_collision_node_;        
00255   Ogre::SceneNode* root_other_node_;
00256 
00257   bool visible_;                                
00258   bool visual_visible_;                         
00259   bool collision_visible_;                      
00260 
00261   DisplayContext* context_;
00262   Property* link_tree_;
00263   EnumProperty* link_tree_style_;
00264   BoolProperty* expand_tree_;
00265   BoolProperty* expand_link_details_;
00266   BoolProperty* expand_joint_details_;
00267   BoolProperty* enable_all_links_;
00268   std::map<LinkTreeStyle, std::string> style_name_map_;
00269   
00270   bool doing_set_checkbox_;   // used only inside setEnableAllLinksCheckbox()
00271   bool robot_loaded_;         // true after robot model is loaded.
00272 
00273   // true inside changedEnableAllLinks().  Prevents calculateJointCheckboxes()
00274   // from recalculating over and over.
00275   bool inChangedEnableAllLinks;
00276 
00277   std::string name_;
00278   float alpha_;
00279 };
00280 
00281 } // namespace rviz
00282 
00283 #endif /* RVIZ_ROBOT_H_ */


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Thu Jun 6 2019 18:02:16