Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #ifndef MARKER_SHAPES_INTERFACE_HPP_
00019 #define MARKER_SHAPES_INTERFACE_HPP_
00020
00021 #include <boost/shared_ptr.hpp>
00022 #include <stdint.h>
00023 #include <visualization_msgs/Marker.h>
00024 #include <fcl/collision_object.h>
00025 #include <fcl/BVH/BVH_model.h>
00026
00027
00029 class IMarkerShape
00030 {
00031 protected:
00032 static uint32_t class_ctr_;
00033 visualization_msgs::Marker marker_;
00034 geometry_msgs::Pose origin_;
00035 bool drawable_;
00036
00037 public:
00038 IMarkerShape();
00039 virtual uint32_t getId() const = 0;
00040 virtual void setColor(double color_r, double color_g, double color_b, double color_a = 1.0) = 0;
00041 virtual visualization_msgs::Marker getMarker() = 0;
00042 virtual void updatePose(const geometry_msgs::Vector3& pos, const geometry_msgs::Quaternion& quat) = 0;
00043 virtual void updatePose(const geometry_msgs::Pose& pose) = 0;
00044 virtual fcl::CollisionObject getCollisionObject() const = 0;
00045 virtual geometry_msgs::Pose getMarkerPose() const = 0;
00046 virtual geometry_msgs::Pose getOriginRelToFrame() const = 0;
00047
00048
00054 inline void setDrawable(bool can_be_drawn)
00055 {
00056 this->drawable_ = can_be_drawn;
00057 }
00058
00059 inline bool isDrawable()
00060 {
00061 return this->drawable_;
00062 }
00063
00064 virtual ~IMarkerShape() {}
00065 };
00066
00067
00068 typedef boost::shared_ptr< IMarkerShape > PtrIMarkerShape_t;
00069 typedef fcl::BVHModel<fcl::RSS> BVH_RSS_t;
00070
00071 #endif