Go to the documentation of this file.
50 robot_description_property_ =
52 "The name of the ROS parameter where the URDF for the robot is loaded",
this,
53 SLOT(changedRobotDescription()),
this);
55 trajectory_visual_ = std::make_shared<TrajectoryVisualization>(
this,
this);
62 Display::onInitialize();
88 catch (std::exception& e)
119 Display::onDisable();
125 Display::update(wall_dt, ros_dt);
131 BoolProperty::setName(
name);
void onInitialize() override
~TrajectoryDisplay() override
void load(const rviz::Config &config) override
void update(float wall_dt, float ros_dt) override
void setName(const QString &name) override
rdf_loader::RDFLoaderPtr rdf_loader_
std::shared_ptr< Model > ModelSharedPtr
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Ogre::SceneNode * scene_node_
std::string getStdString()
void onDisable() override
DisplayContext * context_
moveit::core::RobotModelConstPtr robot_model_
void changedRobotDescription()
Slot Event Functions.
TrajectoryVisualizationPtr trajectory_visual_
virtual void load(const Config &config)
rviz::StringProperty * robot_description_property_
ros::NodeHandle update_nh_
visualization
Author(s): Ioan Sucan
, Dave Coleman , Sachin Chitta
autogenerated on Sat Mar 15 2025 02:27:26