trajectory_visualization.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Dave Coleman */
00036 
00037 #ifndef MOVEIT_TRAJECTORY_RVIZ_PLUGIN__TRAJECTORY_VISUALIZATION
00038 #define MOVEIT_TRAJECTORY_RVIZ_PLUGIN__TRAJECTORY_VISUALIZATION
00039 
00040 #include <moveit/macros/class_forward.h>
00041 #include <rviz/display.h>
00042 #include <rviz/panel_dock_widget.h>
00043 #include <moveit/rviz_plugin_render_tools/robot_state_visualization.h>
00044 #include <moveit/rviz_plugin_render_tools/trajectory_panel.h>
00045 #include <ros/ros.h>
00046 #include <moveit/robot_model/robot_model.h>
00047 #include <moveit/robot_state/robot_state.h>
00048 #include <moveit/robot_trajectory/robot_trajectory.h>
00049 #include <moveit_msgs/DisplayTrajectory.h>
00050 
00051 namespace rviz
00052 {
00053 class Robot;
00054 class Shape;
00055 class Property;
00056 class IntProperty;
00057 class StringProperty;
00058 class BoolProperty;
00059 class FloatProperty;
00060 class RosTopicProperty;
00061 class EditableEnumProperty;
00062 class ColorProperty;
00063 class MovableText;
00064 }
00065 
00066 namespace moveit_rviz_plugin
00067 {
00068 MOVEIT_CLASS_FORWARD(TrajectoryVisualization);
00069 
00070 class TrajectoryVisualization : public QObject
00071 {
00072   Q_OBJECT
00073 
00074 public:
00081   TrajectoryVisualization(rviz::Property* widget, rviz::Display* display);
00082 
00083   virtual ~TrajectoryVisualization();
00084 
00085   virtual void update(float wall_dt, float ros_dt);
00086   virtual void reset();
00087 
00088   void onInitialize(Ogre::SceneNode* scene_node, rviz::DisplayContext* context, ros::NodeHandle update_nh);
00089   void onRobotModelLoaded(robot_model::RobotModelConstPtr robot_model);
00090   void onEnable();
00091   void onDisable();
00092   void setName(const QString& name);
00093 
00094   void dropTrajectory();
00095 
00096 public Q_SLOTS:
00097   void interruptCurrentDisplay();
00098 
00099 private Q_SLOTS:
00100 
00104   void changedDisplayPathVisualEnabled();
00105   void changedDisplayPathCollisionEnabled();
00106   void changedRobotPathAlpha();
00107   void changedLoopDisplay();
00108   void changedShowTrail();
00109   void changedTrailStepSize();
00110   void changedTrajectoryTopic();
00111   void changedStateDisplayTime();
00112   void changedRobotColor();
00113   void enabledRobotColor();
00114   void trajectorySliderPanelVisibilityChange(bool enable);
00115 
00116 protected:
00120   void incomingDisplayTrajectory(const moveit_msgs::DisplayTrajectory::ConstPtr& msg);
00121   float getStateDisplayTime();
00122   void clearTrajectoryTrail();
00123 
00124   // Handles actually drawing the robot along motion plans
00125   RobotStateVisualizationPtr display_path_robot_;
00126 
00127   // Handle colouring of robot
00128   void setRobotColor(rviz::Robot* robot, const QColor& color);
00129   void unsetRobotColor(rviz::Robot* robot);
00130 
00131   robot_trajectory::RobotTrajectoryPtr displaying_trajectory_message_;
00132   robot_trajectory::RobotTrajectoryPtr trajectory_message_to_display_;
00133   std::vector<rviz::Robot*> trajectory_trail_;
00134   ros::Subscriber trajectory_topic_sub_;
00135   bool animating_path_;
00136   bool drop_displaying_trajectory_;
00137   int current_state_;
00138   float current_state_time_;
00139   boost::mutex update_trajectory_message_;
00140 
00141   robot_model::RobotModelConstPtr robot_model_;
00142   robot_state::RobotStatePtr robot_state_;
00143 
00144   // Pointers from parent display taht we save
00145   rviz::Display* display_;  // the parent display that this class populates
00146   rviz::Property* widget_;
00147   Ogre::SceneNode* scene_node_;
00148   rviz::DisplayContext* context_;
00149   ros::NodeHandle update_nh_;
00150   TrajectoryPanel* trajectory_slider_panel_;
00151   rviz::PanelDockWidget* trajectory_slider_dock_panel_;
00152 
00153   // Properties
00154   rviz::BoolProperty* display_path_visual_enabled_property_;
00155   rviz::BoolProperty* display_path_collision_enabled_property_;
00156   rviz::EditableEnumProperty* state_display_time_property_;
00157   rviz::RosTopicProperty* trajectory_topic_property_;
00158   rviz::FloatProperty* robot_path_alpha_property_;
00159   rviz::BoolProperty* loop_display_property_;
00160   rviz::BoolProperty* trail_display_property_;
00161   rviz::BoolProperty* interrupt_display_property_;
00162   rviz::ColorProperty* robot_color_property_;
00163   rviz::BoolProperty* enable_robot_color_property_;
00164   rviz::IntProperty* trail_step_size_property_;
00165 };
00166 
00167 }  // namespace moveit_rviz_plugin
00168 
00169 #endif


visualization
Author(s): Ioan Sucan , Dave Coleman , Sachin Chitta
autogenerated on Wed Jun 19 2019 19:25:00