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 #ifndef MOVEIT_TRAJECTORY_RVIZ_PLUGIN__TRAJECTORY_VISUALIZATION
38 #define MOVEIT_TRAJECTORY_RVIZ_PLUGIN__TRAJECTORY_VISUALIZATION
39 
40 #include <boost/thread/mutex.hpp>
42 #include <rviz/display.h>
43 #include <rviz/panel_dock_widget.h>
44 
45 #ifndef Q_MOC_RUN
48 #include <ros/ros.h>
52 #include <moveit_msgs/DisplayTrajectory.h>
53 #endif
54 
55 namespace rviz
56 {
57 class Robot;
58 class Shape;
59 class Property;
60 class IntProperty;
61 class StringProperty;
62 class BoolProperty;
63 class FloatProperty;
64 class RosTopicProperty;
65 class EditableEnumProperty;
66 class ColorProperty;
67 class MovableText;
68 }
69 
70 namespace moveit_rviz_plugin
71 {
72 MOVEIT_CLASS_FORWARD(TrajectoryVisualization);
73 
74 class TrajectoryVisualization : public QObject
75 {
76  Q_OBJECT
77 
78 public:
86 
87  virtual ~TrajectoryVisualization();
88 
89  virtual void update(float wall_dt, float ros_dt);
90  virtual void reset();
91 
92  void onInitialize(Ogre::SceneNode* scene_node, rviz::DisplayContext* context, ros::NodeHandle update_nh);
93  void onRobotModelLoaded(robot_model::RobotModelConstPtr robot_model);
94  void onEnable();
95  void onDisable();
96  void setName(const QString& name);
97 
98  void dropTrajectory();
99 
100 public Q_SLOTS:
101  void interruptCurrentDisplay();
102  void setDefaultAttachedObjectColor(const QColor& color);
103 
104 private Q_SLOTS:
105 
109  void changedDisplayPathVisualEnabled();
110  void changedDisplayPathCollisionEnabled();
111  void changedRobotPathAlpha();
112  void changedLoopDisplay();
113  void changedShowTrail();
114  void changedTrailStepSize();
115  void changedTrajectoryTopic();
116  void changedStateDisplayTime();
117  void changedRobotColor();
118  void enabledRobotColor();
119  void trajectorySliderPanelVisibilityChange(bool enable);
120 
121 protected:
125  void incomingDisplayTrajectory(const moveit_msgs::DisplayTrajectory::ConstPtr& msg);
126  float getStateDisplayTime();
127  void clearTrajectoryTrail();
128 
129  // Handles actually drawing the robot along motion plans
130  RobotStateVisualizationPtr display_path_robot_;
131 
132  // Handle colouring of robot
133  void setRobotColor(rviz::Robot* robot, const QColor& color);
134  void unsetRobotColor(rviz::Robot* robot);
135 
136  robot_trajectory::RobotTrajectoryPtr displaying_trajectory_message_;
137  robot_trajectory::RobotTrajectoryPtr trajectory_message_to_display_;
138  std::vector<rviz::Robot*> trajectory_trail_;
145 
146  robot_model::RobotModelConstPtr robot_model_;
147  robot_state::RobotStatePtr robot_state_;
148 
149  // Pointers from parent display taht we save
150  rviz::Display* display_; // the parent display that this class populates
152  Ogre::SceneNode* scene_node_;
157 
158  // Properties
170 };
171 
172 } // namespace moveit_rviz_plugin
173 
174 #endif
robot_trajectory::RobotTrajectoryPtr trajectory_message_to_display_
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
robot_trajectory::RobotTrajectoryPtr displaying_trajectory_message_
MOVEIT_CLASS_FORWARD(TrajectoryVisualization)
rviz::EditableEnumProperty * state_display_time_property_


visualization
Author(s): Ioan Sucan , Dave Coleman , Sachin Chitta
autogenerated on Wed Jul 10 2019 04:04:24