Go to the documentation of this file.
39 #include <OgreQuaternion.h>
44 #include <OgrePrerequisites.h>
59 class TransformListener;
83 Robot(Ogre::SceneNode* root_node,
85 const std::string& name,
96 virtual void load(
const urdf::ModelInterface&
urdf,
bool visual =
true,
bool collision =
true);
101 virtual void clear();
188 virtual void setPosition(
const Ogre::Vector3& position);
190 virtual void setScale(
const Ogre::Vector3& scale);
201 const urdf::LinkConstSharedPtr& link,
202 const std::string& parent_joint_name,
std::map< std::string, RobotLink * > M_NameToLink
void setCollisionVisible(bool visible)
Set whether the collision meshes/primitives of the robot should be visible.
BoolProperty * expand_link_details_
M_NameToLink links_
Map of name to link info, stores all loaded links.
bool visual_visible_
Should we show the visual representation?
virtual ~LinkFactory()=default
void changedExpandLinkDetails()
Property * getLinkTreeProperty()
Ogre::SceneNode * root_other_node_
virtual void setScale(const Ogre::Vector3 &scale)
BoolProperty * expand_joint_details_
Ogre::SceneNode * getVisualNode()
Property specialized to provide getter for booleans.
bool isCollisionVisible()
Returns whether or not the collision representation is set to be visible To be visible this and isVis...
void changedHideSubProperties()
LinkFactory * link_factory_
factory for generating links and joints
virtual const Ogre::Vector3 & getPosition()
bool visible_
Should we show anything at all? (affects visual, collision, axes, and trails)
bool inChangedEnableAllLinks
A single element of a property tree, with a name, value, description, and possibly children.
virtual const Ogre::Quaternion & getOrientation()
static bool styleIsTree(LinkTreeStyle style)
void setVisualVisible(bool visible)
Set whether the visual meshes of the robot should be visible.
virtual RobotJoint * createJoint(Robot *robot, const urdf::JointConstSharedPtr &joint)
const std::string & getName()
Ogre::SceneNode * getCollisionNode()
EnumProperty * link_tree_style_
BoolProperty * expand_tree_
const M_NameToJoint & getJoints() const
void addJointToLinkTree(LinkTreeStyle style, Property *parent, RobotJoint *joint)
virtual void setOrientation(const Ogre::Quaternion &orientation)
M_NameToJoint joints_
Map of name to joint info, stores all loaded joints.
Contains any data we need from a joint in the robot.
void addLinkToLinkTree(LinkTreeStyle style, Property *parent, RobotLink *link)
void setLinkTreeStyle(LinkTreeStyle style)
Ogre::SceneNode * root_collision_node_
Node all our collision nodes are children of.
void setEnableAllLinksCheckbox(const QVariant &val)
Pure-virtual base class for objects which give Display subclasses context in which to work.
Ogre::SceneNode * root_visual_node_
Node all our visual nodes are children of.
bool isVisualVisible()
Returns whether or not the visual representation is set to be visible To be visible this and isVisibl...
void changedExpandJointDetails()
void updateLinkVisibilities()
Call RobotLink::updateVisibility() on each link.
void calculateJointCheckboxes()
Ogre::SceneNode * getOtherNode()
virtual void update(const LinkUpdater &updater)
Ogre::SceneManager * getSceneManager()
void useDetailProperty(bool use_detail)
static bool styleShowJoint(LinkTreeStyle style)
bool collision_visible_
Should we show the collision representation?
virtual void setPosition(const Ogre::Vector3 &position)
const M_NameToLink & getLinks() const
Ogre::SceneManager * scene_manager_
Contains any data we need from a link in the robot.
void changedEnableAllLinks()
virtual void setVisible(bool visible)
Set the robot as a whole to be visible or not.
bool isVisible()
Returns whether anything is visible.
void unparentLinkProperties()
RobotLink * getRootLink()
RobotLink * getLink(const std::string &name)
BoolProperty * enable_all_links_
RobotJoint * getJoint(const std::string &name)
std::map< std::string, RobotJoint * > M_NameToJoint
static bool styleShowLink(LinkTreeStyle style)
std::map< LinkTreeStyle, std::string > style_name_map_
Robot(Ogre::SceneNode *root_node, DisplayContext *context, const std::string &name, Property *parent_property)
virtual void load(const urdf::ModelInterface &urdf, bool visual=true, bool collision=true)
Loads meshes/primitives from a robot description. Calls clear() before loading.
DisplayContext * getDisplayContext()
DisplayContext * context_
virtual RobotLink * createLink(Robot *robot, const urdf::LinkConstSharedPtr &link, const std::string &parent_joint_name, bool visual, bool collision)
void changedLinkTreeStyle()
void setLinkFactory(LinkFactory *link_factory)
virtual void clear()
Clears all data loaded from a URDF.
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Dec 13 2024 03:31:02