30 #include <OgreSceneNode.h> 31 #include <OgreSceneManager.h> 51 const std::string& link_name,
52 const std::string& text,
55 display->
setStatus( level, QString::fromStdString( link_name ), QString::fromStdString( text ));
60 , has_new_transforms_( false )
61 , time_since_last_transform_( 0.0
f )
64 "Whether to display the visual representation of the robot.",
68 "Whether to display the collision representation of the robot.",
72 "Interval at which to update the links, in seconds. " 73 " 0 means to update every update cycle.",
78 "Amount of transparency to apply to the links.",
84 "Name of the parameter to search for to load the robot description.",
88 "Robot Model normally assumes the link name is the same as the tf frame name. " 89 " This option allows you to set a prefix. Mainly useful for multi-robot situations.",
160 +
"] does not exist, and was not found by searchParam()" );
165 if( content.empty() )
181 if( !doc.RootElement() )
189 if( !descr.
initXml( doc.RootElement() ))
virtual void update(const LinkUpdater &updater)
virtual void clear()
Clears all data loaded from a URDF.
Property * collision_enabled_property_
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
FloatProperty * alpha_property_
URDF_EXPORT bool initXml(TiXmlElement *xml)
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
virtual float getFloat() const
virtual void onInitialize()
Override this function to do subclass-specific initialization.
Property specialized to enforce floating point max/min.
std::string robot_description_
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Property * visual_enabled_property_
std::string getStdString()
bool isEnabled() const
Return true if this Display is enabled, false if not.
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 void update(float wall_dt, float ros_dt)
Called periodically by the visualization manager.
virtual void clearStatuses()
Delete all status children. This is thread-safe.
virtual void fixedFrameChanged()
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
void setCollisionVisible(bool visible)
Set whether the collision meshes/primitives of the robot should be visible.
virtual void reset()
Called to tell the display to clear its state.
bool searchParam(const std::string &key, std::string &result) const
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
void updateRobotDescription()
void updateVisualVisible()
Robot * robot_
Handles actually drawing the robot.
bool has_new_transforms_
Callback sets this to tell our update function it needs to update the transforms. ...
FloatProperty * update_rate_property_
void linkUpdaterStatusFunction(StatusProperty::Level level, const std::string &link_name, const std::string &text, RobotModelDisplay *display)
Property specialized for string values.
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
Property(const QString &name=QString(), const QVariant default_value=QVariant(), const QString &description=QString(), Property *parent=0, const char *changed_slot=0, QObject *receiver=0)
Constructor.
void setVisualVisible(bool visible)
Set whether the visual meshes of the robot should be visible.
bool getParam(const std::string &key, std::string &s) const
virtual void reset()
Called to tell the display to clear its state.
virtual QVariant getValue() const
Return the value of this Property as a QVariant. If the value has never been set, an invalid QVariant...
virtual void onEnable()
Derived classes override this to do the actual work of enabling themselves.
Uses a robot xml description to display the pieces of a robot at the transforms broadcast by rosTF...
bool initialized() const
Returns true if the display has been initialized.
virtual ~RobotModelDisplay()
virtual void load()
Loads a URDF from the ros-param named by our "Robot Description" property, iterates through the links...
virtual void setVisible(bool visible)
Set the robot as a whole to be visible or not.
StringProperty * tf_prefix_property_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
StringProperty * robot_description_property_
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
virtual QString getName() const
Return the name of this Property as a QString.
void updateCollisionVisible()
virtual void onDisable()
Derived classes override this to do the actual work of disabling themselves.
float time_since_last_transform_