40#include <rviz_common/properties/string_property.hpp>
54 "Robot Description",
"robot_description",
"The name of the ROS parameter where the URDF for the robot is loaded",
55 this, SLOT(changedRobotDescription()),
this);
64 Display::onInitialize();
66 auto ros_node_abstraction = context_->getRosNodeAbstraction().lock();
67 if (!ros_node_abstraction)
69 RCLCPP_INFO(
logger_,
"Unable to lock weak_ptr from DisplayContext in TrajectoryDisplay constructor");
72 node_ = ros_node_abstraction->get_raw_node();
84 setStatus(rviz_common::properties::StatusProperty::Error,
"Robot Model",
88 setStatus(rviz_common::properties::StatusProperty::Ok,
"Robot Model",
"Successfully loaded");
90 const srdf::ModelSharedPtr& srdf =
97 catch (std::exception& e)
99 setStatus(rviz_common::properties::StatusProperty::Error,
"RobotModel", QString(
"Loading failed: %1").arg(e.what()));
115 Display::load(config);
128 Display::onDisable();
134 Display::update(wall_dt, ros_dt);
138void TrajectoryDisplay::changedRobotDescription()
void load(const rviz_common::Config &config) override
rdf_loader::RDFLoaderPtr rdf_loader_
moveit::core::RobotModelConstPtr robot_model_
rclcpp::Node::SharedPtr node_
TrajectoryVisualizationPtr trajectory_visual_
void update(float wall_dt, float ros_dt) override
~TrajectoryDisplay() override
void onInitialize() override
rviz_common::properties::StringProperty * robot_description_property_
void onDisable() override
Main namespace for MoveIt.