#include <robot.h>
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. | |
float | getAlpha () |
Ogre::SceneNode * | getCollisionNode () |
DisplayContext * | getDisplayContext () |
RobotJoint * | getJoint (const std::string &name) |
const M_NameToJoint & | getJoints () const |
RobotLink * | getLink (const std::string &name) |
const M_NameToLink & | getLinks () const |
Property * | getLinkTreeProperty () |
const std::string & | getName () |
virtual const Ogre::Quaternion & | getOrientation () |
Ogre::SceneNode * | getOtherNode () |
virtual const Ogre::Vector3 & | getPosition () |
RobotLink * | getRootLink () |
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. | |
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. | |
virtual void | load (const urdf::ModelInterface &urdf, bool visual=true, bool collision=true) |
Loads meshes/primitives from a robot description. Calls clear() before loading. | |
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. | |
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. | |
void | setVisualVisible (bool visible) |
Set whether the visual meshes of the robot should be visible. | |
virtual void | update (const LinkUpdater &updater) |
virtual | ~Robot () |
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. | |
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? | |
DisplayContext * | context_ |
bool | doing_set_checkbox_ |
BoolProperty * | enable_all_links_ |
BoolProperty * | expand_joint_details_ |
BoolProperty * | expand_link_details_ |
BoolProperty * | expand_tree_ |
bool | inChangedEnableAllLinks |
M_NameToJoint | joints_ |
Map of name to joint info, stores all loaded joints. | |
LinkFactory * | link_factory_ |
factory for generating links and joints | |
Property * | link_tree_ |
EnumProperty * | link_tree_style_ |
M_NameToLink | links_ |
Map of name to link info, stores all loaded links. | |
std::string | name_ |
bool | robot_loaded_ |
Ogre::SceneNode * | root_collision_node_ |
Node all our collision nodes are children of. | |
RobotLink * | root_link_ |
Ogre::SceneNode * | root_other_node_ |
Ogre::SceneNode * | root_visual_node_ |
Node all our visual nodes are children of. | |
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) | |
bool | visual_visible_ |
Should we show the visual representation? | |
Private Slots | |
void | changedEnableAllLinks () |
void | changedExpandJointDetails () |
void | changedExpandLinkDetails () |
void | changedExpandTree () |
void | changedHideSubProperties () |
void | changedLinkTreeStyle () |
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.
typedef std::map< std::string, RobotJoint* > rviz::Robot::M_NameToJoint |
typedef std::map< std::string, RobotLink* > rviz::Robot::M_NameToLink |
Robot::Robot | ( | Ogre::SceneNode * | root_node, |
DisplayContext * | context, | ||
const std::string & | name, | ||
Property * | parent_property | ||
) |
Robot::~Robot | ( | ) | [virtual] |
void Robot::addJointToLinkTree | ( | LinkTreeStyle | style, |
Property * | parent, | ||
RobotJoint * | joint | ||
) | [protected] |
void Robot::addLinkToLinkTree | ( | LinkTreeStyle | style, |
Property * | parent, | ||
RobotLink * | link | ||
) | [protected] |
used by setLinkTreeStyle() to recursively build link & joint tree.
void Robot::calculateJointCheckboxes | ( | ) |
void Robot::changedEnableAllLinks | ( | ) | [private, slot] |
void Robot::changedExpandJointDetails | ( | ) | [private, slot] |
void Robot::changedExpandLinkDetails | ( | ) | [private, slot] |
void Robot::changedExpandTree | ( | ) | [private, slot] |
void Robot::changedHideSubProperties | ( | ) | [private, slot] |
void Robot::changedLinkTreeStyle | ( | ) | [private, slot] |
void Robot::clear | ( | ) | [virtual] |
float rviz::Robot::getAlpha | ( | ) | [inline] |
Ogre::SceneNode* rviz::Robot::getCollisionNode | ( | ) | [inline] |
DisplayContext* rviz::Robot::getDisplayContext | ( | ) | [inline] |
RobotJoint * Robot::getJoint | ( | const std::string & | name | ) |
const M_NameToJoint& rviz::Robot::getJoints | ( | ) | const [inline] |
RobotLink * Robot::getLink | ( | const std::string & | name | ) |
const M_NameToLink& rviz::Robot::getLinks | ( | ) | const [inline] |
Property* rviz::Robot::getLinkTreeProperty | ( | ) | [inline] |
const std::string& rviz::Robot::getName | ( | void | ) | [inline] |
const Ogre::Quaternion & Robot::getOrientation | ( | ) | [virtual] |
Ogre::SceneNode* rviz::Robot::getOtherNode | ( | ) | [inline] |
const Ogre::Vector3 & Robot::getPosition | ( | ) | [virtual] |
RobotLink* rviz::Robot::getRootLink | ( | ) | [inline] |
Ogre::SceneManager* rviz::Robot::getSceneManager | ( | ) | [inline] |
Ogre::SceneNode* rviz::Robot::getVisualNode | ( | ) | [inline] |
void Robot::initLinkTreeStyle | ( | ) | [protected] |
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.
bool Robot::isVisible | ( | ) |
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.
void Robot::load | ( | const urdf::ModelInterface & | urdf, |
bool | visual = true , |
||
bool | collision = true |
||
) | [virtual] |
void Robot::setAlpha | ( | float | a | ) |
void Robot::setCollisionVisible | ( | bool | visible | ) |
void Robot::setEnableAllLinksCheckbox | ( | QVariant | val | ) | [protected] |
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());
void Robot::setLinkTreeStyle | ( | LinkTreeStyle | style | ) |
void Robot::setOrientation | ( | const Ogre::Quaternion & | orientation | ) | [virtual] |
void Robot::setPosition | ( | const Ogre::Vector3 & | position | ) | [virtual] |
void Robot::setScale | ( | const Ogre::Vector3 & | scale | ) | [virtual] |
void Robot::setVisible | ( | bool | visible | ) | [virtual] |
void Robot::setVisualVisible | ( | bool | visible | ) |
bool Robot::styleIsTree | ( | LinkTreeStyle | style | ) | [static, protected] |
bool Robot::styleShowJoint | ( | LinkTreeStyle | style | ) | [static, protected] |
bool Robot::styleShowLink | ( | LinkTreeStyle | style | ) | [static, protected] |
void Robot::unparentLinkProperties | ( | ) | [protected] |
void Robot::update | ( | const LinkUpdater & | updater | ) | [virtual] |
void Robot::updateLinkVisibilities | ( | ) | [protected] |
Call RobotLink::updateVisibility() on each link.
void Robot::useDetailProperty | ( | bool | use_detail | ) | [protected] |
float rviz::Robot::alpha_ [protected] |
bool rviz::Robot::collision_visible_ [protected] |
DisplayContext* rviz::Robot::context_ [protected] |
bool rviz::Robot::doing_set_checkbox_ [protected] |
BoolProperty* rviz::Robot::enable_all_links_ [protected] |
BoolProperty* rviz::Robot::expand_joint_details_ [protected] |
BoolProperty* rviz::Robot::expand_link_details_ [protected] |
BoolProperty* rviz::Robot::expand_tree_ [protected] |
bool rviz::Robot::inChangedEnableAllLinks [protected] |
M_NameToJoint rviz::Robot::joints_ [protected] |
LinkFactory* rviz::Robot::link_factory_ [protected] |
Property* rviz::Robot::link_tree_ [protected] |
EnumProperty* rviz::Robot::link_tree_style_ [protected] |
M_NameToLink rviz::Robot::links_ [protected] |
std::string rviz::Robot::name_ [protected] |
bool rviz::Robot::robot_loaded_ [protected] |
Ogre::SceneNode* rviz::Robot::root_collision_node_ [protected] |
RobotLink* rviz::Robot::root_link_ [protected] |
Ogre::SceneNode* rviz::Robot::root_other_node_ [protected] |
Ogre::SceneNode* rviz::Robot::root_visual_node_ [protected] |
Ogre::SceneManager* rviz::Robot::scene_manager_ [protected] |
std::map<LinkTreeStyle, std::string> rviz::Robot::style_name_map_ [protected] |
bool rviz::Robot::visible_ [protected] |
bool rviz::Robot::visual_visible_ [protected] |