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 
00044 #ifndef Q_MOC_RUN
00045 #include <moveit/rviz_plugin_render_tools/robot_state_visualization.h>
00046 #include <moveit/rviz_plugin_render_tools/trajectory_panel.h>
00047 #include <ros/ros.h>
00048 #include <moveit/robot_model/robot_model.h>
00049 #include <moveit/robot_state/robot_state.h>
00050 #include <moveit/robot_trajectory/robot_trajectory.h>
00051 #include <moveit_msgs/DisplayTrajectory.h>
00052 #endif
00053 
00054 namespace rviz
00055 {
00056 class Robot;
00057 class Shape;
00058 class Property;
00059 class IntProperty;
00060 class StringProperty;
00061 class BoolProperty;
00062 class FloatProperty;
00063 class RosTopicProperty;
00064 class EditableEnumProperty;
00065 class ColorProperty;
00066 class MovableText;
00067 }
00068 
00069 namespace moveit_rviz_plugin
00070 {
00071 MOVEIT_CLASS_FORWARD(TrajectoryVisualization);
00072 
00073 class TrajectoryVisualization : public QObject
00074 {
00075   Q_OBJECT
00076 
00077 public:
00084   TrajectoryVisualization(rviz::Property* widget, rviz::Display* display);
00085 
00086   virtual ~TrajectoryVisualization();
00087 
00088   virtual void update(float wall_dt, float ros_dt);
00089   virtual void reset();
00090 
00091   void onInitialize(Ogre::SceneNode* scene_node, rviz::DisplayContext* context, ros::NodeHandle update_nh);
00092   void onRobotModelLoaded(robot_model::RobotModelConstPtr robot_model);
00093   void onEnable();
00094   void onDisable();
00095   void setName(const QString& name);
00096 
00097   void dropTrajectory();
00098 
00099 public Q_SLOTS:
00100   void interruptCurrentDisplay();
00101 
00102 private Q_SLOTS:
00103 
00107   void changedDisplayPathVisualEnabled();
00108   void changedDisplayPathCollisionEnabled();
00109   void changedRobotPathAlpha();
00110   void changedLoopDisplay();
00111   void changedShowTrail();
00112   void changedTrailStepSize();
00113   void changedTrajectoryTopic();
00114   void changedStateDisplayTime();
00115   void changedRobotColor();
00116   void enabledRobotColor();
00117   void trajectorySliderPanelVisibilityChange(bool enable);
00118 
00119 protected:
00123   void incomingDisplayTrajectory(const moveit_msgs::DisplayTrajectory::ConstPtr& msg);
00124   float getStateDisplayTime();
00125   void clearTrajectoryTrail();
00126 
00127   // Handles actually drawing the robot along motion plans
00128   RobotStateVisualizationPtr display_path_robot_;
00129 
00130   // Handle colouring of robot
00131   void setRobotColor(rviz::Robot* robot, const QColor& color);
00132   void unsetRobotColor(rviz::Robot* robot);
00133 
00134   robot_trajectory::RobotTrajectoryPtr displaying_trajectory_message_;
00135   robot_trajectory::RobotTrajectoryPtr trajectory_message_to_display_;
00136   std::vector<rviz::Robot*> trajectory_trail_;
00137   ros::Subscriber trajectory_topic_sub_;
00138   bool animating_path_;
00139   bool drop_displaying_trajectory_;
00140   int current_state_;
00141   float current_state_time_;
00142   boost::mutex update_trajectory_message_;
00143 
00144   robot_model::RobotModelConstPtr robot_model_;
00145   robot_state::RobotStatePtr robot_state_;
00146 
00147   // Pointers from parent display taht we save
00148   rviz::Display* display_;  // the parent display that this class populates
00149   rviz::Property* widget_;
00150   Ogre::SceneNode* scene_node_;
00151   rviz::DisplayContext* context_;
00152   ros::NodeHandle update_nh_;
00153   TrajectoryPanel* trajectory_slider_panel_;
00154   rviz::PanelDockWidget* trajectory_slider_dock_panel_;
00155 
00156   // Properties
00157   rviz::BoolProperty* display_path_visual_enabled_property_;
00158   rviz::BoolProperty* display_path_collision_enabled_property_;
00159   rviz::EditableEnumProperty* state_display_time_property_;
00160   rviz::RosTopicProperty* trajectory_topic_property_;
00161   rviz::FloatProperty* robot_path_alpha_property_;
00162   rviz::BoolProperty* loop_display_property_;
00163   rviz::BoolProperty* trail_display_property_;
00164   rviz::BoolProperty* interrupt_display_property_;
00165   rviz::ColorProperty* robot_color_property_;
00166   rviz::BoolProperty* enable_robot_color_property_;
00167   rviz::IntProperty* trail_step_size_property_;
00168 };
00169 
00170 }  // namespace moveit_rviz_plugin
00171 
00172 #endif


visualization
Author(s): Ioan Sucan , Dave Coleman , Sachin Chitta
autogenerated on Mon Jul 24 2017 02:22:14