Class Robot

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public QObject

Class Documentation

class Robot : public QObject

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.

Public Types

enum LinkTreeStyle

Values:

enumerator STYLE_DEFAULT
enumerator STYLE_JOINT_LIST
typedef std::map<std::string, RobotLink*> M_NameToLink
typedef std::map<std::string, RobotJoint*> M_NameToJoint

Public Functions

Robot(Ogre::SceneNode *root_node, rviz_common::DisplayContext *context, const std::string &name, rviz_common::properties::Property *parent_property)
~Robot() override
virtual void load(const urdf::ModelInterface &urdf, bool visual = true, bool collision = true, bool mass = true, bool inertia = true)

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

Parameters:
  • urdf – The robot description to read from

  • visual – Whether or not to load the visual representation

  • collision – Whether or not to load the collision representation

  • mass – Whether or not to load the mass representation

  • inertia – Whether or not to load the inertia representation

virtual void clear()

Clears all data loaded from a URDF.

virtual void update(const LinkUpdater &updater)
virtual void setVisible(bool visible)

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

Parameters:

visible – Should we be visible?

void setVisualVisible(bool visible)

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

Parameters:

visible – Whether the visual meshes of the robot should be visible

void setCollisionVisible(bool visible)

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

Parameters:

visible – Whether the collision meshes/primitives should be visible

void setMassVisible(bool visible)

Set whether the mass of each part is visible.

Parameters:

visible – Whether the mass of each link is visible

void setInertiaVisible(bool visible)

Set whether the inertia of each part is visible.

Parameters:

visible – Whether the inertia of each link is visible

bool isVisible()

Returns whether anything is visible.

bool isVisualVisible()

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

bool isCollisionVisible()

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

bool isMassVisible()

Returns whether or not mass of each link is visible. To be visible this and isVisible() must both be true.

bool isInertiaVisible()

Returns whether or not inertia of each link is visible. To be visible this and isVisible() must both be true.

void setAlpha(float a)
inline float getAlpha()
inline RobotLink *getRootLink()
RobotLink *getLink(const std::string &name)
RobotJoint *getJoint(const std::string &name)
inline const M_NameToLink &getLinks() const
inline const M_NameToJoint &getJoints() const
inline const std::string &getName()
inline Ogre::SceneNode *getVisualNode()
inline Ogre::SceneNode *getCollisionNode()
inline Ogre::SceneNode *getOtherNode()
inline Ogre::SceneManager *getSceneManager()
inline rviz_common::DisplayContext *getDisplayContext()
virtual void setPosition(const Ogre::Vector3 &position)
virtual void setOrientation(const Ogre::Quaternion &orientation)
virtual void setScale(const Ogre::Vector3 &scale)
virtual const Ogre::Vector3 &getPosition()
virtual const Ogre::Quaternion &getOrientation()
void 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());

void setLinkTreeStyle(LinkTreeStyle style)

Set the style of the link property.

inline rviz_common::properties::Property *getLinkTreeProperty()

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

void calculateJointCheckboxes()

Protected Functions

void updateLinkVisibilities()

Call RobotLink::updateVisibility() on each link.

void unparentLinkProperties()

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

void useDetailProperty(bool use_detail)

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

void addJointToLinkTree(LinkTreeStyle style, rviz_common::properties::Property *parent, RobotJoint *joint)
void setEnableAllLinksCheckbox(QVariant val)
void initLinkTreeStyle()

initialize style_name_map_ and link_tree_style_ options

Protected Attributes

Ogre::SceneManager *scene_manager_

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

M_NameToJoint joints_

stores all loaded joints.

Map of name to joint info,

factory for generating links and joints

Ogre::SceneNode *root_visual_node_

Node all our visual nodes are children of.

Ogre::SceneNode *root_collision_node_

Node all our collision nodes are children of.

Ogre::SceneNode *root_other_node_
bool visible_

visual, collision, axes, and trails)

Should we show anything at all? (affects

bool visual_visible_

Should we show the visual representation?

bool collision_visible_

Should we show the collision representation?

bool mass_visible_

Should we show mass of each link?

bool inertia_visible_

Should we show inertia of each link?

rviz_common::DisplayContext *context_
rviz_common::properties::BoolProperty *expand_tree_
rviz_common::properties::BoolProperty *expand_joint_details_
std::map<LinkTreeStyle, std::string> style_name_map_
bool doing_set_checkbox_
bool robot_loaded_
std::string name_
float alpha_

Protected Static Functions

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

subclass LinkFactory and call setLinkFactory() to use a subclass of RobotLink and/or RobotJoint.

Public Functions

virtual ~LinkFactory() = default
virtual RobotLink *createLink(Robot *robot, const urdf::LinkConstSharedPtr &link, const std::string &parent_joint_name, bool visual, bool collision, bool mass, bool inertia)
virtual RobotJoint *createJoint(Robot *robot, const urdf::JointConstSharedPtr &joint)