40 #include <rviz_common/properties/string_property.hpp>
46 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit.ros.visualization.trajectory_display");
53 "Robot Description",
"robot_description",
"The name of the ROS parameter where the URDF for the robot is loaded",
54 this, SLOT(changedRobotDescription()),
this);
63 Display::onInitialize();
65 auto ros_node_abstraction = context_->getRosNodeAbstraction().lock();
66 if (!ros_node_abstraction)
68 RCLCPP_INFO(LOGGER,
"Unable to lock weak_ptr from DisplayContext in TrajectoryDisplay constructor");
71 node_ = ros_node_abstraction->get_raw_node();
83 this->setStatus(rviz_common::properties::StatusProperty::Error,
"Robot Model",
87 this->setStatus(rviz_common::properties::StatusProperty::Ok,
"Robot Model",
"Successfully loaded");
89 const srdf::ModelSharedPtr& srdf =
96 catch (std::exception& e)
98 setStatus(rviz_common::properties::StatusProperty::Error,
"RobotModel", QString(
"Loading failed: %1").arg(e.what()));
114 Display::load(config);
127 Display::onDisable();
133 Display::update(wall_dt, ros_dt);
137 void 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
const rclcpp::Logger LOGGER