path_with_velocity_display.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #ifndef TRAJECTORY_TRACKER_RVIZ_PLUGINS_PATH_WITH_VELOCITY_DISPLAY_H
00031 #define TRAJECTORY_TRACKER_RVIZ_PLUGINS_PATH_WITH_VELOCITY_DISPLAY_H
00032 
00033 #include <vector>
00034 
00035 #include <rviz/message_filter_display.h>
00036 #include <rviz/ogre_helpers/arrow.h>
00037 #include <rviz/ogre_helpers/axes.h>
00038 #include <rviz/ogre_helpers/billboard_line.h>
00039 
00040 #include <trajectory_tracker_msgs/PathWithVelocity.h>
00041 #include <trajectory_tracker_msgs/PoseStampedWithVelocity.h>
00042 
00043 namespace Ogre
00044 {
00045 class ManualObject;
00046 }  // namespace Ogre
00047 
00048 namespace rviz
00049 {
00050 class ColorProperty;
00051 class FloatProperty;
00052 class IntProperty;
00053 class EnumProperty;
00054 class BillboardLine;
00055 class VectorProperty;
00056 }  // namespace rviz
00057 
00058 namespace trajectory_tracker_rviz_plugins
00059 {
00064 class PathWithVelocityDisplay : public rviz::MessageFilterDisplay<trajectory_tracker_msgs::PathWithVelocity>
00065 {
00066   Q_OBJECT
00067 public:
00068   PathWithVelocityDisplay();
00069   virtual ~PathWithVelocityDisplay();
00070 
00072   virtual void reset();
00073 
00074 protected:
00076   virtual void onInitialize();
00077 
00079   void processMessage(const trajectory_tracker_msgs::PathWithVelocity::ConstPtr& msg);
00080 
00081 private Q_SLOTS:
00082   void updateBufferLength();
00083   void updateStyle();
00084   void updateLineWidth();
00085   void updateOffset();
00086   void updatePoseStyle();
00087   void updatePoseAxisGeometry();
00088   void updatePoseArrowColor();
00089   void updatePoseArrowGeometry();
00090 
00091 private:
00092   void destroyObjects();
00093   void allocateArrowVector(std::vector<rviz::Arrow*>& arrow_vect, size_t num);
00094   void allocateAxesVector(std::vector<rviz::Axes*>& axes_vect, size_t num);
00095   void destroyPoseAxesChain();
00096   void destroyPoseArrowChain();
00097 
00098   typedef std::vector<rviz::Axes*> AxesPtrArray;
00099   typedef std::vector<rviz::Arrow*> ArrowPtrArray;
00100 
00101   std::vector<Ogre::ManualObject*> manual_objects_;
00102   std::vector<rviz::BillboardLine*> billboard_lines_;
00103   std::vector<AxesPtrArray> axes_chain_;
00104   std::vector<ArrowPtrArray> arrow_chain_;
00105 
00106   rviz::EnumProperty* style_property_;
00107   rviz::ColorProperty* color_property_;
00108   rviz::FloatProperty* alpha_property_;
00109   rviz::FloatProperty* line_width_property_;
00110   rviz::IntProperty* buffer_length_property_;
00111   rviz::VectorProperty* offset_property_;
00112 
00113   enum LineStyle
00114   {
00115     LINES,
00116     BILLBOARDS
00117   };
00118 
00119   // pose marker property
00120   rviz::EnumProperty* pose_style_property_;
00121   rviz::FloatProperty* pose_axes_length_property_;
00122   rviz::FloatProperty* pose_axes_radius_property_;
00123   rviz::ColorProperty* pose_arrow_color_property_;
00124   rviz::FloatProperty* pose_arrow_shaft_length_property_;
00125   rviz::FloatProperty* pose_arrow_head_length_property_;
00126   rviz::FloatProperty* pose_arrow_shaft_diameter_property_;
00127   rviz::FloatProperty* pose_arrow_head_diameter_property_;
00128 
00129   enum PoseStyle
00130   {
00131     NONE,
00132     AXES,
00133     ARROWS,
00134   };
00135 };
00136 
00137 }  // namespace trajectory_tracker_rviz_plugins
00138 
00139 #endif  // TRAJECTORY_TRACKER_RVIZ_PLUGINS_PATH_WITH_VELOCITY_DISPLAY_H


trajectory_tracker_rviz_plugins
Author(s): Atsushi Watanabe
autogenerated on Sat Jun 22 2019 19:29:20