40 #include <rviz_common/display.hpp>
41 #include <rviz_common/panel_dock_widget.hpp>
42 #include <rviz_common/properties/int_property.hpp>
43 #include <rviz_common/properties/ros_topic_property.hpp>
45 #include <rclcpp/logger.hpp>
50 #include <rclcpp/rclcpp.hpp>
54 #include <moveit_msgs/msg/display_trajectory.hpp>
66 class RosTopicProperty;
67 class EditableEnumProperty;
91 virtual void update(
double wall_dt,
double sim_dt);
94 void onInitialize(
const rclcpp::Node::SharedPtr& node, Ogre::SceneNode* scene_node,
95 rviz_common::DisplayContext* context);
113 void changedDisplayPathVisualEnabled();
114 void changedDisplayPathCollisionEnabled();
115 void changedRobotPathAlpha();
116 void changedLoopDisplay();
117 void changedShowTrail();
118 void changedTrailStepSize();
119 void changedTrajectoryTopic();
120 void changedStateDisplayTime();
121 void changedRobotColor();
122 void enabledRobotColor();
123 void trajectorySliderPanelVisibilityChange(
bool enable);
144 void setRobotColor(rviz_default_plugins::robot::Robot* robot,
const QColor& color);
rviz_common::properties::BoolProperty * enable_robot_color_property_
void clearTrajectoryTrail()
void incomingDisplayTrajectory(const moveit_msgs::msg::DisplayTrajectory::ConstSharedPtr &msg)
ROS callback for an incoming path message.
Ogre::SceneNode * scene_node_
rviz_common::DisplayContext * context_
rviz_common::properties::BoolProperty * display_path_visual_enabled_property_
void setName(const QString &name)
rviz_common::properties::BoolProperty * interrupt_display_property_
robot_trajectory::RobotTrajectoryPtr trajectory_message_to_display_
robot_trajectory::RobotTrajectoryPtr displaying_trajectory_message_
std::mutex update_trajectory_message_
rviz_common::PanelDockWidget * trajectory_slider_dock_panel_
void onInitialize(const rclcpp::Node::SharedPtr &node, Ogre::SceneNode *scene_node, rviz_common::DisplayContext *context)
rviz_common::properties::BoolProperty * trail_display_property_
virtual void update(double wall_dt, double sim_dt)
TrajectoryPanel * trajectory_slider_panel_
rviz_common::properties::BoolProperty * display_path_collision_enabled_property_
moveit::core::RobotStatePtr robot_state_
rviz_common::properties::RosTopicProperty * trajectory_topic_property_
moveit::core::RobotModelConstPtr robot_model_
rviz_common::properties::BoolProperty * use_sim_time_property_
TrajectoryVisualization(rviz_common::properties::Property *widget, rviz_common::Display *display)
Playback a trajectory from a planned path.
std_msgs::msg::ColorRGBA default_attached_object_color_
rviz_common::properties::Property * widget_
rviz_common::properties::BoolProperty * loop_display_property_
rviz_common::properties::ColorProperty * robot_color_property_
void setRobotColor(rviz_default_plugins::robot::Robot *robot, const QColor &color)
double current_state_time_
rclcpp::Node::SharedPtr node_
rviz_common::properties::EditableEnumProperty * state_display_time_property_
void setDefaultAttachedObjectColor(const QColor &color)
rviz_common::properties::IntProperty * trail_step_size_property_
void interruptCurrentDisplay()
rviz_common::Display * display_
std::vector< RobotStateVisualizationUniquePtr > trajectory_trail_
void unsetRobotColor(rviz_default_plugins::robot::Robot *robot)
~TrajectoryVisualization() override
void onRobotModelLoaded(const moveit::core::RobotModelConstPtr &robot_model)
RobotStateVisualizationPtr display_path_robot_
rviz_common::properties::FloatProperty * robot_path_alpha_property_
bool drop_displaying_trajectory_
rclcpp::Subscription< moveit_msgs::msg::DisplayTrajectory >::SharedPtr trajectory_topic_sub_
double getStateDisplayTime()
get time to show each single robot state
MOVEIT_CLASS_FORWARD(RobotStateVisualization)