Classes | Public Types | Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Private Slots | List of all members
rviz::Robot Class Reference

#include <robot.h>

Inheritance diagram for rviz::Robot:
Inheritance graph
[legend]

Classes

class  LinkFactory
 

Public Types

enum  LinkTreeStyle {
  STYLE_LINK_LIST, STYLE_DEFAULT = STYLE_LINK_LIST, STYLE_JOINT_LIST, STYLE_LINK_TREE,
  STYLE_JOINT_LINK_TREE
}
 
typedef std::map< std::string, RobotJoint * > M_NameToJoint
 
typedef std::map< std::string, RobotLink * > M_NameToLink
 

Public Member Functions

void calculateJointCheckboxes ()
 
virtual void clear ()
 Clears all data loaded from a URDF. More...
 
float getAlpha ()
 
Ogre::SceneNode * getCollisionNode ()
 
DisplayContextgetDisplayContext ()
 
RobotJointgetJoint (const std::string &name)
 
const M_NameToJointgetJoints () const
 
RobotLinkgetLink (const std::string &name)
 
const M_NameToLinkgetLinks () const
 
PropertygetLinkTreeProperty ()
 
const std::string & getName ()
 
virtual const Ogre::Quaternion & getOrientation ()
 
Ogre::SceneNode * getOtherNode ()
 
virtual const Ogre::Vector3 & getPosition ()
 
RobotLinkgetRootLink ()
 
Ogre::SceneManager * getSceneManager ()
 
Ogre::SceneNode * getVisualNode ()
 
bool isCollisionVisible ()
 Returns whether or not the collision representation is set to be visible To be visible this and isVisible() must both be true. More...
 
bool isVisible ()
 Returns whether anything is visible. More...
 
bool isVisualVisible ()
 Returns whether or not the visual representation is set to be visible To be visible this and isVisible() must both be true. More...
 
virtual void load (const urdf::ModelInterface &urdf, bool visual=true, bool collision=true)
 Loads meshes/primitives from a robot description. Calls clear() before loading. More...
 
 Robot (Ogre::SceneNode *root_node, DisplayContext *context, const std::string &name, Property *parent_property)
 
void setAlpha (float a)
 
void setCollisionVisible (bool visible)
 Set whether the collision meshes/primitives of the robot should be visible. More...
 
void setLinkFactory (LinkFactory *link_factory)
 
void setLinkTreeStyle (LinkTreeStyle style)
 
virtual void setOrientation (const Ogre::Quaternion &orientation)
 
virtual void setPosition (const Ogre::Vector3 &position)
 
virtual void setScale (const Ogre::Vector3 &scale)
 
virtual void setVisible (bool visible)
 Set the robot as a whole to be visible or not. More...
 
void setVisualVisible (bool visible)
 Set whether the visual meshes of the robot should be visible. More...
 
virtual void update (const LinkUpdater &updater)
 
 ~Robot () override
 

Protected Member Functions

void addJointToLinkTree (LinkTreeStyle style, Property *parent, RobotJoint *joint)
 
void addLinkToLinkTree (LinkTreeStyle style, Property *parent, RobotLink *link)
 
void initLinkTreeStyle ()
 
void setEnableAllLinksCheckbox (QVariant val)
 
void unparentLinkProperties ()
 
void updateLinkVisibilities ()
 Call RobotLink::updateVisibility() on each link. More...
 
void useDetailProperty (bool use_detail)
 

Static Protected Member Functions

static bool styleIsTree (LinkTreeStyle style)
 
static bool styleShowJoint (LinkTreeStyle style)
 
static bool styleShowLink (LinkTreeStyle style)
 

Protected Attributes

float alpha_
 
bool collision_visible_
 Should we show the collision representation? More...
 
DisplayContextcontext_
 
bool doing_set_checkbox_
 
BoolPropertyenable_all_links_
 
BoolPropertyexpand_joint_details_
 
BoolPropertyexpand_link_details_
 
BoolPropertyexpand_tree_
 
bool inChangedEnableAllLinks
 
M_NameToJoint joints_
 Map of name to joint info, stores all loaded joints. More...
 
LinkFactorylink_factory_
 factory for generating links and joints More...
 
Propertylink_tree_
 
EnumPropertylink_tree_style_
 
M_NameToLink links_
 Map of name to link info, stores all loaded links. More...
 
std::string name_
 
bool robot_loaded_
 
Ogre::SceneNode * root_collision_node_
 Node all our collision nodes are children of. More...
 
RobotLinkroot_link_
 
Ogre::SceneNode * root_other_node_
 
Ogre::SceneNode * root_visual_node_
 Node all our visual nodes are children of. More...
 
Ogre::SceneManager * scene_manager_
 
std::map< LinkTreeStyle, std::string > style_name_map_
 
bool visible_
 Should we show anything at all? (affects visual, collision, axes, and trails) More...
 
bool visual_visible_
 Should we show the visual representation? More...
 

Private Slots

void changedEnableAllLinks ()
 
void changedExpandJointDetails ()
 
void changedExpandLinkDetails ()
 
void changedExpandTree ()
 
void changedHideSubProperties ()
 
void changedLinkTreeStyle ()
 

Detailed Description

A helper class to draw a representation of a robot, as specified by a URDF. Can display either the visual models of the robot, or the collision models.

Definition at line 84 of file robot.h.

Member Typedef Documentation

◆ M_NameToJoint

typedef std::map<std::string, RobotJoint*> rviz::Robot::M_NameToJoint

Definition at line 157 of file robot.h.

◆ M_NameToLink

typedef std::map<std::string, RobotLink*> rviz::Robot::M_NameToLink

Definition at line 156 of file robot.h.

Member Enumeration Documentation

◆ LinkTreeStyle

Enumerator
STYLE_LINK_LIST 
STYLE_DEFAULT 
STYLE_JOINT_LIST 
STYLE_LINK_TREE 
STYLE_JOINT_LINK_TREE 

Definition at line 225 of file robot.h.

Constructor & Destructor Documentation

◆ Robot()

Robot::Robot ( Ogre::SceneNode *  root_node,
DisplayContext context,
const std::string &  name,
Property parent_property 
)

Definition at line 56 of file robot.cpp.

◆ ~Robot()

Robot::~Robot ( )
override

Definition at line 100 of file robot.cpp.

Member Function Documentation

◆ addJointToLinkTree()

void Robot::addJointToLinkTree ( LinkTreeStyle  style,
Property parent,
RobotJoint joint 
)
protected

Definition at line 606 of file robot.cpp.

◆ addLinkToLinkTree()

void Robot::addLinkToLinkTree ( LinkTreeStyle  style,
Property parent,
RobotLink link 
)
protected

used by setLinkTreeStyle() to recursively build link & joint tree.

Definition at line 585 of file robot.cpp.

◆ calculateJointCheckboxes()

void Robot::calculateJointCheckboxes ( )

Definition at line 646 of file robot.cpp.

◆ changedEnableAllLinks

void Robot::changedEnableAllLinks ( )
privateslot

Definition at line 411 of file robot.cpp.

◆ changedExpandJointDetails

void Robot::changedExpandJointDetails ( )
privateslot

Definition at line 399 of file robot.cpp.

◆ changedExpandLinkDetails

void Robot::changedExpandLinkDetails ( )
privateslot

Definition at line 387 of file robot.cpp.

◆ changedExpandTree

void Robot::changedExpandTree ( )
privateslot

Definition at line 343 of file robot.cpp.

◆ changedHideSubProperties

void Robot::changedHideSubProperties ( )
privateslot

Definition at line 368 of file robot.cpp.

◆ changedLinkTreeStyle

void Robot::changedLinkTreeStyle ( )
privateslot

Definition at line 494 of file robot.cpp.

◆ clear()

void Robot::clear ( )
virtual

Clears all data loaded from a URDF.

Definition at line 189 of file robot.cpp.

◆ getAlpha()

float rviz::Robot::getAlpha ( )
inline

Definition at line 144 of file robot.h.

◆ getCollisionNode()

Ogre::SceneNode* rviz::Robot::getCollisionNode ( )
inline

Definition at line 176 of file robot.h.

◆ getDisplayContext()

DisplayContext* rviz::Robot::getDisplayContext ( )
inline

Definition at line 188 of file robot.h.

◆ getJoint()

RobotJoint * Robot::getJoint ( const std::string &  name)

Definition at line 634 of file robot.cpp.

◆ getJoints()

const M_NameToJoint& rviz::Robot::getJoints ( ) const
inline

Definition at line 162 of file robot.h.

◆ getLink()

RobotLink * Robot::getLink ( const std::string &  name)

Definition at line 622 of file robot.cpp.

◆ getLinks()

const M_NameToLink& rviz::Robot::getLinks ( ) const
inline

Definition at line 158 of file robot.h.

◆ getLinkTreeProperty()

Property* rviz::Robot::getLinkTreeProperty ( )
inline

can be used to change the name, reparent, or add extra properties to the list of links

Definition at line 238 of file robot.h.

◆ getName()

const std::string& rviz::Robot::getName ( )
inline

Definition at line 167 of file robot.h.

◆ getOrientation()

const Ogre::Quaternion & Robot::getOrientation ( )
virtual

Definition at line 792 of file robot.cpp.

◆ getOtherNode()

Ogre::SceneNode* rviz::Robot::getOtherNode ( )
inline

Definition at line 180 of file robot.h.

◆ getPosition()

const Ogre::Vector3 & Robot::getPosition ( )
virtual

Definition at line 787 of file robot.cpp.

◆ getRootLink()

RobotLink* rviz::Robot::getRootLink ( )
inline

Definition at line 149 of file robot.h.

◆ getSceneManager()

Ogre::SceneManager* rviz::Robot::getSceneManager ( )
inline

Definition at line 184 of file robot.h.

◆ getVisualNode()

Ogre::SceneNode* rviz::Robot::getVisualNode ( )
inline

Definition at line 172 of file robot.h.

◆ initLinkTreeStyle()

void Robot::initLinkTreeStyle ( )
protected

initialize style_name_map_ and link_tree_style_ options

Definition at line 452 of file robot.cpp.

◆ isCollisionVisible()

bool Robot::isCollisionVisible ( )

Returns whether or not the collision representation is set to be visible To be visible this and isVisible() must both be true.

Definition at line 170 of file robot.cpp.

◆ isVisible()

bool Robot::isVisible ( )

Returns whether anything is visible.

Definition at line 160 of file robot.cpp.

◆ isVisualVisible()

bool Robot::isVisualVisible ( )

Returns whether or not the visual representation is set to be visible To be visible this and isVisible() must both be true.

Definition at line 165 of file robot.cpp.

◆ load()

void Robot::load ( const urdf::ModelInterface &  urdf,
bool  visual = true,
bool  collision = true 
)
virtual

Loads meshes/primitives from a robot description. Calls clear() before loading.

Parameters
urdfThe robot description to read from
visualWhether or not to load the visual representation
collisionWhether or not to load the collision representation

Definition at line 233 of file robot.cpp.

◆ setAlpha()

void Robot::setAlpha ( float  a)

Definition at line 175 of file robot.cpp.

◆ setCollisionVisible()

void Robot::setCollisionVisible ( bool  visible)

Set whether the collision meshes/primitives of the robot should be visible.

Parameters
visibleWhether the collision meshes/primitives should be visible

Definition at line 143 of file robot.cpp.

◆ setEnableAllLinksCheckbox()

void Robot::setEnableAllLinksCheckbox ( QVariant  val)
protected

Definition at line 443 of file robot.cpp.

◆ setLinkFactory()

void Robot::setLinkFactory ( LinkFactory link_factory)

Call this before load() to subclass the RobotLink or RobotJoint class used in the link property. Example: class MyLinkFactory : public LinkFactory { ... // overload createLink() and/or createJoint() } ... robot->setLinkFactory(new MyLinkFactory());

Definition at line 111 of file robot.cpp.

◆ setLinkTreeStyle()

void Robot::setLinkTreeStyle ( LinkTreeStyle  style)

Set the style of the link property.

Definition at line 484 of file robot.cpp.

◆ setOrientation()

void Robot::setOrientation ( const Ogre::Quaternion &  orientation)
virtual

Definition at line 775 of file robot.cpp.

◆ setPosition()

void Robot::setPosition ( const Ogre::Vector3 &  position)
virtual

Definition at line 769 of file robot.cpp.

◆ setScale()

void Robot::setScale ( const Ogre::Vector3 &  scale)
virtual

Definition at line 781 of file robot.cpp.

◆ setVisible()

void Robot::setVisible ( bool  visible)
virtual

Set the robot as a whole to be visible or not.

Parameters
visibleShould we be visible?

Definition at line 120 of file robot.cpp.

◆ setVisualVisible()

void Robot::setVisualVisible ( bool  visible)

Set whether the visual meshes of the robot should be visible.

Parameters
visibleWhether the visual meshes of the robot should be visible

Definition at line 137 of file robot.cpp.

◆ styleIsTree()

bool Robot::styleIsTree ( LinkTreeStyle  style)
staticprotected

Definition at line 479 of file robot.cpp.

◆ styleShowJoint()

bool Robot::styleShowJoint ( LinkTreeStyle  style)
staticprotected

Definition at line 474 of file robot.cpp.

◆ styleShowLink()

bool Robot::styleShowLink ( LinkTreeStyle  style)
staticprotected

Definition at line 469 of file robot.cpp.

◆ unparentLinkProperties()

void Robot::unparentLinkProperties ( )
protected

remove all link and joint properties from their parents. Needed before deletion and before rearranging link tree.

Definition at line 305 of file robot.cpp.

◆ update()

void Robot::update ( const LinkUpdater updater)
virtual

Definition at line 700 of file robot.cpp.

◆ updateLinkVisibilities()

void Robot::updateLinkVisibilities ( )
protected

Call RobotLink::updateVisibility() on each link.

Definition at line 149 of file robot.cpp.

◆ useDetailProperty()

void Robot::useDetailProperty ( bool  use_detail)
protected

Definition at line 324 of file robot.cpp.

Member Data Documentation

◆ alpha_

float rviz::Robot::alpha_
protected

Definition at line 311 of file robot.h.

◆ collision_visible_

bool rviz::Robot::collision_visible_
protected

Should we show the collision representation?

Definition at line 292 of file robot.h.

◆ context_

DisplayContext* rviz::Robot::context_
protected

Definition at line 294 of file robot.h.

◆ doing_set_checkbox_

bool rviz::Robot::doing_set_checkbox_
protected

Definition at line 303 of file robot.h.

◆ enable_all_links_

BoolProperty* rviz::Robot::enable_all_links_
protected

Definition at line 300 of file robot.h.

◆ expand_joint_details_

BoolProperty* rviz::Robot::expand_joint_details_
protected

Definition at line 299 of file robot.h.

◆ expand_link_details_

BoolProperty* rviz::Robot::expand_link_details_
protected

Definition at line 298 of file robot.h.

◆ expand_tree_

BoolProperty* rviz::Robot::expand_tree_
protected

Definition at line 297 of file robot.h.

◆ inChangedEnableAllLinks

bool rviz::Robot::inChangedEnableAllLinks
protected

Definition at line 308 of file robot.h.

◆ joints_

M_NameToJoint rviz::Robot::joints_
protected

Map of name to joint info, stores all loaded joints.

Definition at line 281 of file robot.h.

◆ link_factory_

LinkFactory* rviz::Robot::link_factory_
protected

factory for generating links and joints

Definition at line 284 of file robot.h.

◆ link_tree_

Property* rviz::Robot::link_tree_
protected

Definition at line 295 of file robot.h.

◆ link_tree_style_

EnumProperty* rviz::Robot::link_tree_style_
protected

Definition at line 296 of file robot.h.

◆ links_

M_NameToLink rviz::Robot::links_
protected

Map of name to link info, stores all loaded links.

Definition at line 280 of file robot.h.

◆ name_

std::string rviz::Robot::name_
protected

Definition at line 310 of file robot.h.

◆ robot_loaded_

bool rviz::Robot::robot_loaded_
protected

Definition at line 304 of file robot.h.

◆ root_collision_node_

Ogre::SceneNode* rviz::Robot::root_collision_node_
protected

Node all our collision nodes are children of.

Definition at line 287 of file robot.h.

◆ root_link_

RobotLink* rviz::Robot::root_link_
protected

Definition at line 282 of file robot.h.

◆ root_other_node_

Ogre::SceneNode* rviz::Robot::root_other_node_
protected

Definition at line 288 of file robot.h.

◆ root_visual_node_

Ogre::SceneNode* rviz::Robot::root_visual_node_
protected

Node all our visual nodes are children of.

Definition at line 286 of file robot.h.

◆ scene_manager_

Ogre::SceneManager* rviz::Robot::scene_manager_
protected

Definition at line 278 of file robot.h.

◆ style_name_map_

std::map<LinkTreeStyle, std::string> rviz::Robot::style_name_map_
protected

Definition at line 301 of file robot.h.

◆ visible_

bool rviz::Robot::visible_
protected

Should we show anything at all? (affects visual, collision, axes, and trails)

Definition at line 290 of file robot.h.

◆ visual_visible_

bool rviz::Robot::visual_visible_
protected

Should we show the visual representation?

Definition at line 291 of file robot.h.


The documentation for this class was generated from the following files:


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:26