42 #include <urdf_model/model.h> 44 #include <OgreSceneNode.h> 45 #include <OgreSceneManager.h> 46 #include <OgreEntity.h> 47 #include <OgreMaterialManager.h> 48 #include <OgreMaterial.h> 49 #include <OgreResourceGroupManager.h> 58 : scene_manager_( context->getSceneManager() )
60 , visual_visible_( true )
61 , collision_visible_( false )
64 , doing_set_checkbox_( false )
65 , robot_loaded_( false )
66 , inChangedEnableAllLinks( false )
84 "How the list of links is displayed",
92 "Expand or collapse link tree",
97 "Expand Link Details",
99 "Expand link details (sub properties) to see all info for all links.",
104 "Expand Joint Details",
106 "Expand joint details (sub properties) to see all info for all joints.",
113 "Turn all links on or off.",
169 M_NameToLink::iterator it =
links_.begin();
170 M_NameToLink::iterator end =
links_.end();
171 for ( ; it != end; ++it )
197 M_NameToLink::iterator it =
links_.begin();
198 M_NameToLink::iterator end =
links_.end();
199 for ( ; it != end; ++it )
214 M_NameToLink::iterator link_it =
links_.begin();
215 M_NameToLink::iterator link_end =
links_.end();
216 for ( ; link_it != link_end; ++link_it )
222 M_NameToJoint::iterator joint_it =
joints_.begin();
223 M_NameToJoint::iterator joint_end =
joints_.end();
224 for ( ; joint_it != joint_end; ++joint_it )
239 const urdf::LinkConstSharedPtr& link,
240 const std::string& parent_joint_name,
244 return new RobotLink(robot, link, parent_joint_name, visual, collision);
249 const urdf::JointConstSharedPtr& joint)
268 typedef std::map<std::string, urdf::LinkSharedPtr > M_NameToUrdfLink;
269 M_NameToUrdfLink::const_iterator link_it = urdf.links_.begin();
270 M_NameToUrdfLink::const_iterator link_end = urdf.links_.end();
271 for( ; link_it != link_end; ++link_it )
273 const urdf::LinkConstSharedPtr& urdf_link = link_it->second;
274 std::string parent_joint_name;
276 if (urdf_link != urdf.getRoot() && urdf_link->parent_joint)
278 parent_joint_name = urdf_link->parent_joint->name;
287 if (urdf_link == urdf.getRoot())
292 links_[urdf_link->name] = link;
301 typedef std::map<std::string, urdf::JointSharedPtr > M_NameToUrdfJoint;
302 M_NameToUrdfJoint::const_iterator joint_it = urdf.joints_.begin();
303 M_NameToUrdfJoint::const_iterator joint_end = urdf.joints_.end();
304 for( ; joint_it != joint_end; ++joint_it )
306 const urdf::JointConstSharedPtr& urdf_joint = joint_it->second;
309 joints_[urdf_joint->name] = joint;
333 M_NameToLink::iterator link_it =
links_.begin();
334 M_NameToLink::iterator link_end =
links_.end();
335 for ( ; link_it != link_end ; ++link_it )
337 link_it->second->setParentProperty(
NULL);
341 M_NameToJoint::iterator joint_it =
joints_.begin();
342 M_NameToJoint::iterator joint_end =
joints_.end();
343 for ( ; joint_it != joint_end ; ++joint_it )
345 joint_it->second->setParentProperty(
NULL);
352 M_NameToLink::iterator link_it =
links_.begin();
353 M_NameToLink::iterator link_end =
links_.end();
354 for ( ; link_it != link_end ; ++link_it )
356 link_it->second->useDetailProperty(use_detail);
360 M_NameToJoint::iterator joint_it =
joints_.begin();
361 M_NameToJoint::iterator joint_end =
joints_.end();
362 for ( ; joint_it != joint_end ; ++joint_it )
364 joint_it->second->useDetailProperty(use_detail);
372 M_NameToLink::iterator link_it =
links_.begin();
373 M_NameToLink::iterator link_end =
links_.end();
374 for ( ; link_it != link_end ; ++link_it )
377 link_it->second->getLinkProperty()->expand();
379 link_it->second->getLinkProperty()->collapse();
382 M_NameToJoint::iterator joint_it =
joints_.begin();
383 M_NameToJoint::iterator joint_end =
joints_.end();
384 for ( ; joint_it != joint_end ; ++joint_it )
387 joint_it->second->getJointProperty()->expand();
389 joint_it->second->getJointProperty()->collapse();
397 M_NameToLink::iterator link_it =
links_.begin();
398 M_NameToLink::iterator link_end =
links_.end();
399 for ( ; link_it != link_end ; ++link_it )
401 link_it->second->hideSubProperties(hide);
404 M_NameToJoint::iterator joint_it =
joints_.begin();
405 M_NameToJoint::iterator joint_end =
joints_.end();
406 for ( ; joint_it != joint_end ; ++joint_it )
408 joint_it->second->hideSubProperties(hide);
416 M_NameToLink::iterator link_it =
links_.begin();
417 M_NameToLink::iterator link_end =
links_.end();
418 for ( ; link_it != link_end ; ++link_it )
420 link_it->second->expandDetails(expand);
428 M_NameToJoint::iterator joint_it =
joints_.begin();
429 M_NameToJoint::iterator joint_end =
joints_.end();
430 for ( ; joint_it != joint_end ; ++joint_it )
432 joint_it->second->expandDetails(expand);
445 M_NameToLink::iterator link_it =
links_.begin();
446 M_NameToLink::iterator link_end =
links_.end();
447 for ( ; link_it != link_end ; ++link_it )
449 if (link_it->second->hasGeometry())
451 link_it->second->getLinkProperty()->setValue(enable);
455 M_NameToJoint::iterator joint_it =
joints_.begin();
456 M_NameToJoint::iterator joint_end =
joints_.end();
457 for ( ; joint_it != joint_end ; ++joint_it )
459 if (joint_it->second->hasDescendentLinksWithGeometry())
461 joint_it->second->getJointProperty()->setValue(enable);
486 std::map<LinkTreeStyle, std::string>::const_iterator style_it =
style_name_map_.begin();
487 std::map<LinkTreeStyle, std::string>::const_iterator style_end =
style_name_map_.end();
488 for ( ; style_it != style_end ; ++style_it )
518 std::map<LinkTreeStyle, std::string>::const_iterator style_it =
style_name_map_.find(style);
551 M_NameToJoint::iterator joint_it =
joints_.begin();
552 M_NameToJoint::iterator joint_end =
joints_.end();
553 for ( ; joint_it != joint_end ; ++joint_it )
555 joint_it->second->setParentProperty(
link_tree_);
556 joint_it->second->setJointPropertyDescription();
564 M_NameToLink::iterator link_it =
links_.begin();
565 M_NameToLink::iterator link_end =
links_.end();
566 for ( ; link_it != link_end ; ++link_it )
568 link_it->second->setParentProperty(
link_tree_);
622 std::vector<std::string>::const_iterator child_joint_it = link->
getChildJointNames().begin();
623 std::vector<std::string>::const_iterator child_joint_end = link->
getChildJointNames().end();
624 for ( ; child_joint_it != child_joint_end ; ++child_joint_it )
653 M_NameToLink::iterator it =
links_.find( name );
656 ROS_WARN(
"Link [%s] does not exist", name.c_str() );
665 M_NameToJoint::iterator it =
joints_.find( name );
668 ROS_WARN(
"Joint [%s] does not exist", name.c_str() );
680 int links_with_geom_checked = 0;
681 int links_with_geom_unchecked = 0;
695 links_with_geom_checked += checked ? 1 : 0;
696 links_with_geom_unchecked += checked ? 0 : 1;
698 int links_with_geom = links_with_geom_checked + links_with_geom_unchecked;
701 std::vector<std::string>::const_iterator child_joint_it = link->
getChildJointNames().begin();
702 std::vector<std::string>::const_iterator child_joint_end = link->
getChildJointNames().end();
703 for ( ; child_joint_it != child_joint_end ; ++child_joint_it )
708 int child_links_with_geom;
709 int child_links_with_geom_checked;
710 int child_links_with_geom_unchecked;
712 links_with_geom_checked += child_links_with_geom_checked;
713 links_with_geom_unchecked += child_links_with_geom_unchecked;
716 links_with_geom = links_with_geom_checked + links_with_geom_unchecked;
718 if (!links_with_geom)
730 M_NameToLink::iterator link_it =
links_.begin();
731 M_NameToLink::iterator link_end =
links_.end();
732 for ( ; link_it != link_end; ++link_it )
738 Ogre::Vector3 visual_position, collision_position;
739 Ogre::Quaternion visual_orientation, collision_orientation;
741 visual_position, visual_orientation,
742 collision_position, collision_orientation
746 if (visual_orientation.isNaN())
750 "visual orientation of %s contains NaNs. Skipping render as long as the orientation is invalid.",
755 if (visual_position.isNaN())
759 "visual position of %s contains NaNs. Skipping render as long as the position is invalid.",
764 if (collision_orientation.isNaN())
768 "collision orientation of %s contains NaNs. Skipping render as long as the orientation is invalid.",
773 if (collision_position.isNaN())
777 "collision position of %s contains NaNs. Skipping render as long as the position is invalid.",
782 link->
setTransforms( visual_position, visual_orientation, collision_position, collision_orientation );
784 std::vector<std::string>::const_iterator joint_it = link->
getChildJointNames().begin();
785 std::vector<std::string>::const_iterator joint_end = link->
getChildJointNames().end();
786 for ( ; joint_it != joint_end ; ++joint_it )
void updateVisibility()
Update the visibility of the link elements: visual mesh, collision mesh, trail, and axes...
virtual void update(const LinkUpdater &updater)
void setParentProperty(Property *new_parent)
Robot(Ogre::SceneNode *root_node, DisplayContext *context, const std::string &name, Property *parent_property)
void setEnableAllLinksCheckbox(QVariant val)
void addLinkToLinkTree(LinkTreeStyle style, Property *parent, RobotLink *link)
void setJointPropertyDescription()
M_NameToJoint joints_
Map of name to joint info, stores all loaded joints.
virtual void clear()
Clears all data loaded from a URDF.
virtual bool setValue(const QVariant &new_value)
Set the new value for this property. Returns true if the new value is different from the old value...
void useDetailProperty(bool use_detail)
A single element of a property tree, with a name, value, description, and possibly children...
void calculateJointCheckboxesRecursive(int &links_with_geom, int &links_with_geom_checked, int &links_with_geom_unchecked)
virtual void clearOptions()
Clear the list of options.
virtual void setName(const QString &name)
Set the name.
void changedLinkTreeStyle()
BoolProperty * expand_joint_details_
LinkFactory * link_factory_
factory for generating links and joints
virtual void setPosition(const Ogre::Vector3 &position)
virtual RobotLink * createLink(Robot *robot, const urdf::LinkConstSharedPtr &link, const std::string &parent_joint_name, bool visual, bool collision)
void setTransforms(const Ogre::Vector3 &parent_link_position, const Ogre::Quaternion &parent_link_orientation)
virtual const Ogre::Vector3 & getPosition()
virtual void setDescription(const QString &description)
Set the description.
RobotLink * getLink(const std::string &name)
bool isCollisionVisible()
Returns whether or not the collision representation is set to be visible To be visible this and isVis...
void calculateJointCheckboxes()
void setToErrorMaterial()
std::map< LinkTreeStyle, std::string > style_name_map_
static bool styleShowJoint(LinkTreeStyle style)
virtual void load(const urdf::ModelInterface &urdf, bool visual=true, bool collision=true)
Loads meshes/primitives from a robot description. Calls clear() before loading.
virtual bool getBool() const
virtual void collapse()
Collapse (hide the children of) this Property.
bool visual_visible_
Should we show the visual representation?
virtual void setTransforms(const Ogre::Vector3 &visual_position, const Ogre::Quaternion &visual_orientation, const Ogre::Vector3 &collision_position, const Ogre::Quaternion &collision_orientation)
virtual void setScale(const Ogre::Vector3 &scale)
const std::string & getName() const
void setLinkFactory(LinkFactory *link_factory)
void changedExpandLinkDetails()
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.
void setCollisionVisible(bool visible)
Set whether the collision meshes/primitives of the robot should be visible.
void setLinkTreeStyle(LinkTreeStyle style)
void show()
Show this Property in any PropertyTreeWidgets.
bool isVisible()
Returns whether anything is visible.
#define ROS_ERROR_THROTTLE(period,...)
void updateLinkVisibilities()
Call RobotLink::updateVisibility() on each link.
void changedExpandJointDetails()
BoolProperty * enable_all_links_
BoolProperty * expand_tree_
virtual bool getLinkTransforms(const std::string &link_name, Ogre::Vector3 &visual_position, Ogre::Quaternion &visual_orientation, Ogre::Vector3 &collision_position, Ogre::Quaternion &collision_orientation) const =0
Property * getLinkProperty() const
void addJointToLinkTree(LinkTreeStyle style, Property *parent, RobotJoint *joint)
void addOptionStd(const std::string &option, int value=0)
Contains any data we need from a joint in the robot.
virtual void setOrientation(const Ogre::Quaternion &orientation)
void setRobotAlpha(float a)
Ogre::SceneManager * scene_manager_
Contains any data we need from a link in the robot.
void setToNormalMaterial()
bool visible_
Should we show anything at all? (affects visual, collision, axes, and trails)
bool inChangedEnableAllLinks
BoolProperty * expand_link_details_
virtual void setRobotAlpha(float a)
const std::vector< std::string > & getChildJointNames() const
Property specialized to provide getter for booleans.
const Property * getJointProperty() const
static bool styleShowLink(LinkTreeStyle style)
void setVisualVisible(bool visible)
Set whether the visual meshes of the robot should be visible.
void changedHideSubProperties()
EnumProperty * link_tree_style_
virtual QVariant getValue() const
Return the value of this Property as a QVariant. If the value has never been set, an invalid QVariant...
Ogre::SceneNode * root_other_node_
virtual RobotJoint * createJoint(Robot *robot, const urdf::JointConstSharedPtr &joint)
void hide()
Hide this Property in any PropertyTreeWidgets.
const std::string & getChildLinkName() const
bool collision_visible_
Should we show the collision representation?
Ogre::SceneNode * root_collision_node_
Node all our collision nodes are children of.
virtual void setVisible(bool visible)
Set the robot as a whole to be visible or not.
virtual int getOptionInt()
Return the int value of the currently-chosen option, or 0 if the current option string does not have ...
virtual const Ogre::Quaternion & getOrientation()
M_NameToLink links_
Map of name to link info, stores all loaded links.
bool isVisualVisible()
Returns whether or not the visual representation is set to be visible To be visible this and isVisibl...
void changedEnableAllLinks()
static bool styleIsTree(LinkTreeStyle style)
void unparentLinkProperties()
RobotJoint * getJoint(const std::string &name)
void setParentProperty(Property *new_parent)