#include <trajectory_visualization.h>
Definition at line 75 of file trajectory_visualization.h.
◆ TrajectoryVisualization()
moveit_rviz_plugin::TrajectoryVisualization::TrajectoryVisualization |
( |
rviz_common::properties::Property * |
widget, |
|
|
rviz_common::Display * |
display |
|
) |
| |
Playback a trajectory from a planned path.
- Parameters
-
widget | - either a rviz::Display or rviz::Property |
display | - the rviz::Display from the parent |
- Returns
- true on success
Definition at line 67 of file trajectory_visualization.cpp.
◆ ~TrajectoryVisualization()
moveit_rviz_plugin::TrajectoryVisualization::~TrajectoryVisualization |
( |
| ) |
|
|
override |
◆ clearRobotModel()
void moveit_rviz_plugin::TrajectoryVisualization::clearRobotModel |
( |
| ) |
|
◆ clearTrajectoryTrail()
void moveit_rviz_plugin::TrajectoryVisualization::clearTrajectoryTrail |
( |
| ) |
|
|
protected |
◆ dropTrajectory()
void moveit_rviz_plugin::TrajectoryVisualization::dropTrajectory |
( |
| ) |
|
◆ getStateDisplayTime()
float moveit_rviz_plugin::TrajectoryVisualization::getStateDisplayTime |
( |
| ) |
|
|
protected |
get time to show each single robot state
- Returns
- Positive values indicate a fixed time per state Negative values indicate a realtime-factor
Definition at line 366 of file trajectory_visualization.cpp.
◆ incomingDisplayTrajectory()
void moveit_rviz_plugin::TrajectoryVisualization::incomingDisplayTrajectory |
( |
const moveit_msgs::msg::DisplayTrajectory::ConstSharedPtr & |
msg | ) |
|
|
protected |
◆ interruptCurrentDisplay
void moveit_rviz_plugin::TrajectoryVisualization::interruptCurrentDisplay |
( |
| ) |
|
|
slot |
◆ onDisable()
void moveit_rviz_plugin::TrajectoryVisualization::onDisable |
( |
| ) |
|
◆ onEnable()
void moveit_rviz_plugin::TrajectoryVisualization::onEnable |
( |
| ) |
|
◆ onInitialize()
void moveit_rviz_plugin::TrajectoryVisualization::onInitialize |
( |
const rclcpp::Node::SharedPtr & |
node, |
|
|
Ogre::SceneNode * |
scene_node, |
|
|
rviz_common::DisplayContext * |
context |
|
) |
| |
◆ onRobotModelLoaded()
void moveit_rviz_plugin::TrajectoryVisualization::onRobotModelLoaded |
( |
const moveit::core::RobotModelConstPtr & |
robot_model | ) |
|
◆ reset()
void moveit_rviz_plugin::TrajectoryVisualization::reset |
( |
| ) |
|
|
virtual |
◆ setDefaultAttachedObjectColor
void moveit_rviz_plugin::TrajectoryVisualization::setDefaultAttachedObjectColor |
( |
const QColor & |
color | ) |
|
|
slot |
◆ setName()
void moveit_rviz_plugin::TrajectoryVisualization::setName |
( |
const QString & |
name | ) |
|
◆ setRobotColor()
void moveit_rviz_plugin::TrajectoryVisualization::setRobotColor |
( |
rviz_default_plugins::robot::Robot * |
robot, |
|
|
const QColor & |
color |
|
) |
| |
|
protected |
◆ unsetRobotColor()
void moveit_rviz_plugin::TrajectoryVisualization::unsetRobotColor |
( |
rviz_default_plugins::robot::Robot * |
robot | ) |
|
|
protected |
◆ update()
void moveit_rviz_plugin::TrajectoryVisualization::update |
( |
float |
wall_dt, |
|
|
float |
sim_dt |
|
) |
| |
|
virtual |
◆ animating_path_
bool moveit_rviz_plugin::TrajectoryVisualization::animating_path_ |
|
protected |
◆ context_
rviz_common::DisplayContext* moveit_rviz_plugin::TrajectoryVisualization::context_ |
|
protected |
◆ current_state_
int moveit_rviz_plugin::TrajectoryVisualization::current_state_ |
|
protected |
◆ current_state_time_
float moveit_rviz_plugin::TrajectoryVisualization::current_state_time_ |
|
protected |
◆ default_attached_object_color_
std_msgs::msg::ColorRGBA moveit_rviz_plugin::TrajectoryVisualization::default_attached_object_color_ |
|
protected |
◆ display_
rviz_common::Display* moveit_rviz_plugin::TrajectoryVisualization::display_ |
|
protected |
◆ display_path_collision_enabled_property_
rviz_common::properties::BoolProperty* moveit_rviz_plugin::TrajectoryVisualization::display_path_collision_enabled_property_ |
|
protected |
◆ display_path_robot_
RobotStateVisualizationPtr moveit_rviz_plugin::TrajectoryVisualization::display_path_robot_ |
|
protected |
◆ display_path_visual_enabled_property_
rviz_common::properties::BoolProperty* moveit_rviz_plugin::TrajectoryVisualization::display_path_visual_enabled_property_ |
|
protected |
◆ displaying_trajectory_message_
robot_trajectory::RobotTrajectoryPtr moveit_rviz_plugin::TrajectoryVisualization::displaying_trajectory_message_ |
|
protected |
◆ drop_displaying_trajectory_
bool moveit_rviz_plugin::TrajectoryVisualization::drop_displaying_trajectory_ |
|
protected |
◆ enable_robot_color_property_
rviz_common::properties::BoolProperty* moveit_rviz_plugin::TrajectoryVisualization::enable_robot_color_property_ |
|
protected |
◆ interrupt_display_property_
rviz_common::properties::BoolProperty* moveit_rviz_plugin::TrajectoryVisualization::interrupt_display_property_ |
|
protected |
◆ loop_display_property_
rviz_common::properties::BoolProperty* moveit_rviz_plugin::TrajectoryVisualization::loop_display_property_ |
|
protected |
◆ node_
rclcpp::Node::SharedPtr moveit_rviz_plugin::TrajectoryVisualization::node_ |
|
protected |
◆ robot_color_property_
rviz_common::properties::ColorProperty* moveit_rviz_plugin::TrajectoryVisualization::robot_color_property_ |
|
protected |
◆ robot_model_
moveit::core::RobotModelConstPtr moveit_rviz_plugin::TrajectoryVisualization::robot_model_ |
|
protected |
◆ robot_path_alpha_property_
rviz_common::properties::FloatProperty* moveit_rviz_plugin::TrajectoryVisualization::robot_path_alpha_property_ |
|
protected |
◆ robot_state_
moveit::core::RobotStatePtr moveit_rviz_plugin::TrajectoryVisualization::robot_state_ |
|
protected |
◆ scene_node_
Ogre::SceneNode* moveit_rviz_plugin::TrajectoryVisualization::scene_node_ |
|
protected |
◆ state_display_time_property_
rviz_common::properties::EditableEnumProperty* moveit_rviz_plugin::TrajectoryVisualization::state_display_time_property_ |
|
protected |
◆ trail_display_property_
rviz_common::properties::BoolProperty* moveit_rviz_plugin::TrajectoryVisualization::trail_display_property_ |
|
protected |
◆ trail_step_size_property_
rviz_common::properties::IntProperty* moveit_rviz_plugin::TrajectoryVisualization::trail_step_size_property_ |
|
protected |
◆ trajectory_message_to_display_
robot_trajectory::RobotTrajectoryPtr moveit_rviz_plugin::TrajectoryVisualization::trajectory_message_to_display_ |
|
protected |
◆ trajectory_slider_dock_panel_
rviz_common::PanelDockWidget* moveit_rviz_plugin::TrajectoryVisualization::trajectory_slider_dock_panel_ |
|
protected |
◆ trajectory_slider_panel_
TrajectoryPanel* moveit_rviz_plugin::TrajectoryVisualization::trajectory_slider_panel_ |
|
protected |
◆ trajectory_topic_property_
rviz_common::properties::RosTopicProperty* moveit_rviz_plugin::TrajectoryVisualization::trajectory_topic_property_ |
|
protected |
◆ trajectory_topic_sub_
rclcpp::Subscription<moveit_msgs::msg::DisplayTrajectory>::SharedPtr moveit_rviz_plugin::TrajectoryVisualization::trajectory_topic_sub_ |
|
protected |
◆ trajectory_trail_
std::vector<RobotStateVisualizationUniquePtr> moveit_rviz_plugin::TrajectoryVisualization::trajectory_trail_ |
|
protected |
◆ update_trajectory_message_
std::mutex moveit_rviz_plugin::TrajectoryVisualization::update_trajectory_message_ |
|
protected |
◆ use_sim_time_property_
rviz_common::properties::BoolProperty* moveit_rviz_plugin::TrajectoryVisualization::use_sim_time_property_ |
|
protected |
◆ widget_
rviz_common::properties::Property* moveit_rviz_plugin::TrajectoryVisualization::widget_ |
|
protected |
The documentation for this class was generated from the following files: