Go to the documentation of this file.
30 #include <OgreSceneNode.h>
31 #include <OgreSceneManager.h>
49 const std::string& link_name,
50 const std::string& text,
53 display->
setStatus(level, QString::fromStdString(link_name), QString::fromStdString(text));
57 :
Display(), has_new_transforms_(false), time_since_last_transform_(0.0
f)
60 new Property(
"Visual Enabled",
true,
"Whether to display the visual representation of the robot.",
64 new Property(
"Collision Enabled",
false,
65 "Whether to display the collision representation of the robot.",
this,
69 "Interval at which to update the links, in seconds. "
70 "0 means to update every update cycle.",
81 "Name of the parameter to search for to load the robot description.",
this,
86 "Robot Model normally assumes the link name is the same as the tf frame name. "
87 " This option allows you to set a prefix. Mainly useful for multi-robot situations.",
155 QString(
"Parameter [%1] does not exist, and was not found by searchParam()")
167 QString(
"Invalid parameter name: %1.\n%2")
196 std::stringstream ss;
199 const std::string& err = name_link_pair.second->getGeometryErrors();
201 ss <<
"\n• for link '" << name_link_pair.first <<
"':\n" << err;
205 QString(
"Errors loading geometries:").
append(ss.str().c_str()));
209 boost::placeholders::_2, boost::placeholders::_3,
this),
235 boost::placeholders::_2, boost::placeholders::_3,
this),
void setCollisionVisible(bool visible)
Set whether the collision meshes/primitives of the robot should be visible.
void reset() override
Called to tell the display to clear its state.
bool isEnabled() const
Return true if this Display is enabled, false if not.
Property * collision_enabled_property_
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
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.
StringProperty * tf_prefix_property_
bool getParam(const std::string &key, bool &b) const
virtual void clearStatuses()
Delete all status children. This is thread-safe.
float time_since_last_transform_
virtual QVariant getValue() const
Return the value of this Property as a QVariant. If the value has never been set, an invalid QVariant...
Property(const QString &name=QString(), const QVariant &default_value=QVariant(), const QString &description=QString(), Property *parent=nullptr)
Constructor.
~RobotModelDisplay() override
void linkUpdaterStatusFunction(StatusProperty::Level level, const std::string &link_name, const std::string &text, RobotModelDisplay *display)
Property specialized to enforce floating point max/min.
std::string robot_description_
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
void updateVisualVisible()
void onEnable() override
Derived classes override this to do the actual work of enabling themselves.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void setVisualVisible(bool visible)
Set whether the visual meshes of the robot should be visible.
virtual float getFloat() const
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
void onDisable() override
Derived classes override this to do the actual work of disabling themselves.
FloatProperty * update_rate_property_
Property specialized for string values.
void onInitialize() override
Override this function to do subclass-specific initialization.
std::string getStdString()
bool searchParam(const std::string &key, std::string &result) const
URDF_EXPORT bool initString(const std::string &xmlstring)
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
void updateRobotDescription()
StringProperty * robot_description_property_
virtual void load()
Loads a URDF from the ros-param named by our "Robot Description" property, iterates through the links...
virtual void update(const LinkUpdater &updater)
virtual QString getName() const
Return the name of this Property as a QString.
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
FloatProperty * alpha_property_
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
Robot * robot_
Handles actually drawing the robot.
void fixedFrameChanged() override
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
const M_NameToLink & getLinks() const
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
virtual void reset()
Called to tell the display to clear its state.
virtual void setVisible(bool visible)
Set the robot as a whole to be visible or 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.
Property * visual_enabled_property_
void updateCollisionVisible()
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
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