moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajectory_visualization.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Dave Coleman */
36 
37 #pragma once
38 
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>
44 #include <mutex>
45 
46 #ifndef Q_MOC_RUN
49 #include <rclcpp/rclcpp.hpp>
53 #include <moveit_msgs/msg/display_trajectory.hpp>
54 #endif
55 
56 namespace rviz
57 {
58 class Robot;
59 class Shape;
60 class Property;
61 class IntProperty;
62 class StringProperty;
63 class BoolProperty;
64 class FloatProperty;
65 class RosTopicProperty;
66 class EditableEnumProperty;
67 class ColorProperty;
68 class MovableText;
69 } // namespace rviz
70 
71 namespace moveit_rviz_plugin
72 {
73 MOVEIT_CLASS_FORWARD(TrajectoryVisualization); // Defines TrajectoryVisualizationPtr, ConstPtr, WeakPtr... etc
74 
75 class TrajectoryVisualization : public QObject
76 {
77  Q_OBJECT
78 
79 public:
86  TrajectoryVisualization(rviz_common::properties::Property* widget, rviz_common::Display* display);
87 
88  ~TrajectoryVisualization() override;
89 
90  virtual void update(float wall_dt, float sim_dt);
91  virtual void reset();
92 
93  void onInitialize(const rclcpp::Node::SharedPtr& node, Ogre::SceneNode* scene_node,
94  rviz_common::DisplayContext* context);
95  void clearRobotModel();
96  void onRobotModelLoaded(const moveit::core::RobotModelConstPtr& robot_model);
97  void onEnable();
98  void onDisable();
99  void setName(const QString& name);
100 
101  void dropTrajectory();
102 
103 public Q_SLOTS:
105  void setDefaultAttachedObjectColor(const QColor& color);
106 
107 private Q_SLOTS:
108 
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);
123 
124 protected:
128  void incomingDisplayTrajectory(const moveit_msgs::msg::DisplayTrajectory::ConstSharedPtr& msg);
129 
135  float getStateDisplayTime();
136  void clearTrajectoryTrail();
137 
138  // Handles actually drawing the robot along motion plans
139  RobotStateVisualizationPtr display_path_robot_;
140  std_msgs::msg::ColorRGBA default_attached_object_color_;
141 
142  // Handle colouring of robot
143  void setRobotColor(rviz_default_plugins::robot::Robot* robot, const QColor& color);
144  void unsetRobotColor(rviz_default_plugins::robot::Robot* robot);
145 
146  robot_trajectory::RobotTrajectoryPtr displaying_trajectory_message_;
147  robot_trajectory::RobotTrajectoryPtr trajectory_message_to_display_;
148  std::vector<RobotStateVisualizationUniquePtr> trajectory_trail_;
149  rclcpp::Subscription<moveit_msgs::msg::DisplayTrajectory>::SharedPtr trajectory_topic_sub_;
155 
156  moveit::core::RobotModelConstPtr robot_model_;
157  moveit::core::RobotStatePtr robot_state_;
158 
159  // Pointers from parent display that we save
160  rviz_common::Display* display_; // the parent display that this class populates
161  rviz_common::properties::Property* widget_;
162  Ogre::SceneNode* scene_node_;
163  rviz_common::DisplayContext* context_;
164  rclcpp::Node::SharedPtr node_;
166  rviz_common::PanelDockWidget* trajectory_slider_dock_panel_;
167 
168  // Properties
169  rviz_common::properties::BoolProperty* display_path_visual_enabled_property_;
170  rviz_common::properties::BoolProperty* display_path_collision_enabled_property_;
171  rviz_common::properties::EditableEnumProperty* state_display_time_property_;
172  rviz_common::properties::RosTopicProperty* trajectory_topic_property_;
173  rviz_common::properties::FloatProperty* robot_path_alpha_property_;
174  rviz_common::properties::BoolProperty* loop_display_property_;
175  rviz_common::properties::BoolProperty* use_sim_time_property_;
176  rviz_common::properties::BoolProperty* trail_display_property_;
177  rviz_common::properties::BoolProperty* interrupt_display_property_;
178  rviz_common::properties::ColorProperty* robot_color_property_;
179  rviz_common::properties::BoolProperty* enable_robot_color_property_;
180  rviz_common::properties::IntProperty* trail_step_size_property_;
181 };
182 
183 } // namespace moveit_rviz_plugin
rviz_common::properties::BoolProperty * enable_robot_color_property_
void incomingDisplayTrajectory(const moveit_msgs::msg::DisplayTrajectory::ConstSharedPtr &msg)
ROS callback for an incoming path message.
rviz_common::properties::BoolProperty * display_path_visual_enabled_property_
rviz_common::properties::BoolProperty * interrupt_display_property_
robot_trajectory::RobotTrajectoryPtr trajectory_message_to_display_
robot_trajectory::RobotTrajectoryPtr displaying_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_
rviz_common::properties::BoolProperty * display_path_collision_enabled_property_
rviz_common::properties::RosTopicProperty * trajectory_topic_property_
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.
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
rviz_common::properties::EditableEnumProperty * state_display_time_property_
rviz_common::properties::IntProperty * trail_step_size_property_
std::vector< RobotStateVisualizationUniquePtr > trajectory_trail_
void unsetRobotColor(rviz_default_plugins::robot::Robot *robot)
void onRobotModelLoaded(const moveit::core::RobotModelConstPtr &robot_model)
virtual void update(float wall_dt, float sim_dt)
rviz_common::properties::FloatProperty * robot_path_alpha_property_
rclcpp::Subscription< moveit_msgs::msg::DisplayTrajectory >::SharedPtr trajectory_topic_sub_
MOVEIT_CLASS_FORWARD(RobotStateVisualization)
robot
Definition: pick.py:53
name
Definition: setup.py:7