robot_link.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_LINK_H
00031 #define RVIZ_ROBOT_LINK_H
00032 
00033 #include <string>
00034 #include <map>
00035 
00036 #include <QObject>
00037 
00038 #ifndef Q_MOC_RUN
00039 #include <OgreVector3.h>
00040 #include <OgreQuaternion.h>
00041 #include <OgreAny.h>
00042 #include <OgreMaterial.h>
00043 #include <OgreSharedPtr.h>
00044 
00045 #include <urdf/model.h> // can be replaced later by urdf_model/types.h
00046 #include <urdf_model/pose.h>
00047 #endif
00048 
00049 #include "rviz/ogre_helpers/object.h"
00050 #include "rviz/selection/forwards.h"
00051 
00052 namespace Ogre
00053 {
00054 class SceneManager;
00055 class Entity;
00056 class SubEntity;
00057 class SceneNode;
00058 class Vector3;
00059 class Quaternion;
00060 class Any;
00061 class RibbonTrail;
00062 }
00063 
00064 namespace rviz
00065 {
00066 class Shape;
00067 class Axes;
00068 class DisplayContext;
00069 class FloatProperty;
00070 class Property;
00071 class BoolProperty;
00072 class QuaternionProperty;
00073 class Robot;
00074 class RobotLinkSelectionHandler;
00075 class VectorProperty;
00076 class RobotJoint;
00077 typedef boost::shared_ptr<RobotLinkSelectionHandler> RobotLinkSelectionHandlerPtr;
00078 
00079 
00084 class RobotLink: public QObject
00085 {
00086 Q_OBJECT
00087 public:
00088   RobotLink( Robot* robot,
00089              const urdf::LinkConstSharedPtr& link,
00090              const std::string& parent_joint_name,
00091              bool visual,
00092              bool collision);
00093   virtual ~RobotLink();
00094 
00095   virtual void setRobotAlpha(float a);
00096 
00097   virtual void setTransforms(const Ogre::Vector3& visual_position, const Ogre::Quaternion& visual_orientation,
00098                      const Ogre::Vector3& collision_position, const Ogre::Quaternion& collision_orientation);
00099 
00100   // access
00101   const std::string& getName() const { return name_; }
00102   const std::string& getParentJointName() const { return parent_joint_name_; }
00103   const std::vector<std::string>& getChildJointNames() const { return child_joint_names_; }
00104   Property* getLinkProperty() const { return link_property_; }
00105   Ogre::SceneNode* getVisualNode() const { return visual_node_; }
00106   Ogre::SceneNode* getCollisionNode() const { return collision_node_; }
00107   Robot* getRobot() const { return robot_; }
00108 
00109   // Remove link_property_ from its old parent and add to new_parent.  If new_parent==NULL then leav unparented.
00110   void setParentProperty(Property* new_parent);
00111 
00112   // hide or show all sub properties (hide to make tree easier to see)
00113   virtual void hideSubProperties(bool hide);
00114 
00115   void setToErrorMaterial();
00116   void setToNormalMaterial();
00117 
00118   void setColor( float red, float green, float blue );
00119   void unsetColor();
00120 
00122   bool setSelectable( bool selectable );
00123   bool getSelectable();
00124 
00125   Ogre::Vector3 getPosition();
00126   Ogre::Quaternion getOrientation();
00127 
00128   bool hasGeometry() const;
00129 
00130   /* If set to true, the link will only render to the depth channel
00131    * and be in render group 0, so it is rendered before anything else.
00132    * Thus, it will occlude other objects without being visible.
00133    */
00134   void setOnlyRenderDepth( bool onlyRenderDepth );
00135   bool getOnlyRenderDepth() const { return only_render_depth_; }
00136 
00137   // place subproperties as children of details_ or joint_property_
00138   void useDetailProperty(bool use_detail);
00139 
00140   // expand all sub properties
00141   void expandDetails(bool expand);
00142 
00143 public Q_SLOTS:
00148   void updateVisibility();
00149 
00150 private Q_SLOTS:
00151   void updateAlpha();
00152   void updateTrail();
00153   void updateAxes();
00154 
00155 private:
00156   void setRenderQueueGroup( Ogre::uint8 group );
00157   bool getEnabled() const;
00158   void createEntityForGeometryElement( const urdf::LinkConstSharedPtr& link, const urdf::Geometry& geom, const urdf::Pose& origin, const std::string material_name, Ogre::SceneNode* scene_node, Ogre::Entity*& entity );
00159 
00160   void createVisual( const urdf::LinkConstSharedPtr& link);
00161   void createCollision( const urdf::LinkConstSharedPtr& link);
00162   void createSelection();
00163   Ogre::MaterialPtr getMaterialForLink( const urdf::LinkConstSharedPtr& link, const std::string material_name = "" );
00164 
00165 
00166 protected:
00167   Robot* robot_;
00168   Ogre::SceneManager* scene_manager_;
00169   DisplayContext* context_;
00170 
00171   std::string name_;                          
00172   std::string parent_joint_name_;
00173   std::vector<std::string> child_joint_names_;
00174 
00175   
00176 
00177   // properties
00178   Property* link_property_;
00179   Property* details_;
00180   VectorProperty* position_property_;
00181   QuaternionProperty* orientation_property_;
00182   Property* trail_property_;
00183   Property* axes_property_;
00184   FloatProperty* alpha_property_;
00185 
00186 private:
00187   typedef std::map<Ogre::SubEntity*, Ogre::MaterialPtr> M_SubEntityToMaterial;
00188   M_SubEntityToMaterial materials_;
00189   Ogre::MaterialPtr default_material_;
00190   std::string default_material_name_;
00191 
00192   std::vector<Ogre::Entity*> visual_meshes_;    
00193   std::vector<Ogre::Entity*> collision_meshes_; 
00194 
00195   Ogre::SceneNode* visual_node_;              
00196   Ogre::SceneNode* collision_node_;           
00197 
00198   Ogre::RibbonTrail* trail_;
00199 
00200   Axes* axes_;
00201 
00202   float material_alpha_; 
00203   float robot_alpha_; 
00204 
00205   bool only_render_depth_;
00206   bool is_selectable_;
00207 
00208   // joint stuff
00209   std::string joint_name_;
00210 
00211   RobotLinkSelectionHandlerPtr selection_handler_;
00212 
00213   Ogre::MaterialPtr color_material_;
00214   bool using_color_;
00215 
00216   friend class RobotLinkSelectionHandler;
00217 };
00218 
00219 } // namespace rviz
00220 
00221 #endif // RVIZ_ROBOT_LINK_H


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Tue Oct 3 2017 03:19:31