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> 
   49 #include <rclcpp/rclcpp.hpp> 
   53 #include <moveit_msgs/msg/display_trajectory.hpp> 
   65 class RosTopicProperty;
 
   66 class EditableEnumProperty;
 
   90   virtual void update(
float wall_dt, 
float sim_dt);
 
   93   void onInitialize(
const rclcpp::Node::SharedPtr& node, Ogre::SceneNode* scene_node,
 
   94                     rviz_common::DisplayContext* context);
 
  112   void changedDisplayPathVisualEnabled();
 
  113   void changedDisplayPathCollisionEnabled();
 
  114   void changedRobotPathAlpha();
 
  115   void changedLoopDisplay();
 
  116   void changedShowTrail();
 
  117   void changedTrailStepSize();
 
  118   void changedTrajectoryTopic();
 
  119   void changedStateDisplayTime();
 
  120   void changedRobotColor();
 
  121   void enabledRobotColor();
 
  122   void trajectorySliderPanelVisibilityChange(
bool enable);
 
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_
 
TrajectoryPanel * trajectory_slider_panel_
 
float current_state_time_
 
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)
 
float getStateDisplayTime()
get time to show each single robot state
 
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)
 
virtual void update(float wall_dt, float sim_dt)
 
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_
 
MOVEIT_CLASS_FORWARD(RobotStateVisualization)