Go to the documentation of this file.
39 #include <boost/thread/mutex.hpp>
51 #include <moveit_msgs/DisplayTrajectory.h>
63 class RosTopicProperty;
64 class EditableEnumProperty;
88 virtual void update(
float wall_dt,
float sim_dt);
moveit::core::RobotStatePtr robot_state_
TrajectoryVisualization(rviz::Property *widget, rviz::Display *display)
Playback a trajectory from a planned path.
rviz::DisplayContext * context_
float getStateDisplayTime()
get time to show each single robot state
void interruptCurrentDisplay()
rviz::BoolProperty * use_sim_time_property_
rviz::IntProperty * trail_step_size_property_
rviz::EditableEnumProperty * state_display_time_property_
void trajectorySliderPanelVisibilityChange(bool enable)
moveit::core::RobotModelConstPtr robot_model_
MOVEIT_CLASS_FORWARD(RobotStateVisualization)
robot_trajectory::RobotTrajectoryPtr displaying_trajectory_message_
std::vector< RobotStateVisualizationUniquePtr > trajectory_trail_
rviz::PanelDockWidget * trajectory_slider_dock_panel_
void onRobotModelLoaded(const moveit::core::RobotModelConstPtr &robot_model)
rviz::BoolProperty * display_path_visual_enabled_property_
void onInitialize(Ogre::SceneNode *scene_node, rviz::DisplayContext *context, const ros::NodeHandle &update_nh)
rviz::BoolProperty * enable_robot_color_property_
bool drop_displaying_trajectory_
Ogre::SceneNode * scene_node_
virtual void update(float wall_dt, float sim_dt)
void setDefaultAttachedObjectColor(const QColor &color)
ros::NodeHandle update_nh_
rviz::BoolProperty * loop_display_property_
ros::Subscriber trajectory_topic_sub_
TrajectoryPanel * trajectory_slider_panel_
std_msgs::ColorRGBA default_attached_object_color_
void incomingDisplayTrajectory(const moveit_msgs::DisplayTrajectory::ConstPtr &msg)
ROS callback for an incoming path message.
void changedDisplayPathVisualEnabled()
Slot Event Functions.
RobotStateVisualizationPtr display_path_robot_
void changedStateDisplayTime()
float current_state_time_
rviz::BoolProperty * display_path_collision_enabled_property_
void changedLoopDisplay()
rviz::BoolProperty * interrupt_display_property_
rviz::BoolProperty * trail_display_property_
void clearTrajectoryTrail()
void changedTrajectoryTopic()
void changedTrailStepSize()
~TrajectoryVisualization() override
void changedDisplayPathCollisionEnabled()
robot_trajectory::RobotTrajectoryPtr trajectory_message_to_display_
rviz::RosTopicProperty * trajectory_topic_property_
void changedRobotPathAlpha()
void unsetRobotColor(rviz::Robot *robot)
rviz::FloatProperty * robot_path_alpha_property_
void setRobotColor(rviz::Robot *robot, const QColor &color)
rviz::ColorProperty * robot_color_property_
boost::mutex update_trajectory_message_
void setName(const QString &name)
visualization
Author(s): Ioan Sucan
, Dave Coleman , Sachin Chitta
autogenerated on Sat Mar 15 2025 02:27:26