moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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#include <rclcpp/logger.hpp>
46
47#ifndef Q_MOC_RUN
50#include <rclcpp/rclcpp.hpp>
54#include <moveit_msgs/msg/display_trajectory.hpp>
55#endif
56
57namespace rviz
58{
59class Robot;
60class Shape;
61class Property;
62class IntProperty;
63class StringProperty;
64class BoolProperty;
65class FloatProperty;
66class RosTopicProperty;
67class EditableEnumProperty;
68class ColorProperty;
69class MovableText;
70} // namespace rviz
71
72namespace moveit_rviz_plugin
73{
74MOVEIT_CLASS_FORWARD(TrajectoryVisualization); // Defines TrajectoryVisualizationPtr, ConstPtr, WeakPtr... etc
75
76class TrajectoryVisualization : public QObject
77{
78 Q_OBJECT
79
80public:
87 TrajectoryVisualization(rviz_common::properties::Property* widget, rviz_common::Display* display);
88
89 ~TrajectoryVisualization() override;
90
91 virtual void update(double wall_dt, double sim_dt);
92 virtual void reset();
93
94 void onInitialize(const rclcpp::Node::SharedPtr& node, Ogre::SceneNode* scene_node,
95 rviz_common::DisplayContext* context);
96 void clearRobotModel();
97 void onRobotModelLoaded(const moveit::core::RobotModelConstPtr& robot_model);
98 void onEnable();
99 void onDisable();
100 void setName(const QString& name);
101
102 void dropTrajectory();
103
104public Q_SLOTS:
106 void setDefaultAttachedObjectColor(const QColor& color);
107
108private Q_SLOTS:
109
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);
124
125protected:
129 void incomingDisplayTrajectory(const moveit_msgs::msg::DisplayTrajectory::ConstSharedPtr& msg);
130
136 double getStateDisplayTime();
138
139 // Handles actually drawing the robot along motion plans
140 RobotStateVisualizationPtr display_path_robot_;
141 std_msgs::msg::ColorRGBA default_attached_object_color_;
142
143 // Handle colouring of robot
144 void setRobotColor(rviz_default_plugins::robot::Robot* robot, const QColor& color);
145 void unsetRobotColor(rviz_default_plugins::robot::Robot* robot);
146
147 robot_trajectory::RobotTrajectoryPtr displaying_trajectory_message_;
148 robot_trajectory::RobotTrajectoryPtr trajectory_message_to_display_;
149 std::vector<RobotStateVisualizationUniquePtr> trajectory_trail_;
150 rclcpp::Subscription<moveit_msgs::msg::DisplayTrajectory>::SharedPtr trajectory_topic_sub_;
156
157 moveit::core::RobotModelConstPtr robot_model_;
158 moveit::core::RobotStatePtr robot_state_;
159
160 // Pointers from parent display that we save
161 rviz_common::Display* display_; // the parent display that this class populates
162 rviz_common::properties::Property* widget_;
163 Ogre::SceneNode* scene_node_;
164 rviz_common::DisplayContext* context_;
165 rclcpp::Node::SharedPtr node_;
167 rviz_common::PanelDockWidget* trajectory_slider_dock_panel_;
168 rclcpp::Logger logger_;
169
170 // Properties
171 rviz_common::properties::BoolProperty* display_path_visual_enabled_property_;
172 rviz_common::properties::BoolProperty* display_path_collision_enabled_property_;
173 rviz_common::properties::EditableEnumProperty* state_display_time_property_;
174 rviz_common::properties::RosTopicProperty* trajectory_topic_property_;
175 rviz_common::properties::FloatProperty* robot_path_alpha_property_;
176 rviz_common::properties::BoolProperty* loop_display_property_;
177 rviz_common::properties::BoolProperty* use_sim_time_property_;
178 rviz_common::properties::BoolProperty* trail_display_property_;
179 rviz_common::properties::BoolProperty* interrupt_display_property_;
180 rviz_common::properties::ColorProperty* robot_color_property_;
181 rviz_common::properties::BoolProperty* enable_robot_color_property_;
182 rviz_common::properties::IntProperty* trail_step_size_property_;
183};
184
185} // namespace moveit_rviz_plugin
#define MOVEIT_CLASS_FORWARD(C)
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_
virtual void update(double wall_dt, double sim_dt)
rviz_common::properties::BoolProperty * display_path_collision_enabled_property_
rviz_common::properties::RosTopicProperty * trajectory_topic_property_
rviz_common::properties::BoolProperty * use_sim_time_property_
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)
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)
rviz_common::properties::FloatProperty * robot_path_alpha_property_
rclcpp::Subscription< moveit_msgs::msg::DisplayTrajectory >::SharedPtr trajectory_topic_sub_
double getStateDisplayTime()
get time to show each single robot state