18 #ifndef MARKER_SHAPES_INTERFACE_HPP_ 19 #define MARKER_SHAPES_INTERFACE_HPP_ 21 #include <boost/shared_ptr.hpp> 23 #include <visualization_msgs/Marker.h> 24 #include <fcl/collision_object.h> 25 #include <fcl/BVH/BVH_model.h> 39 virtual uint32_t
getId()
const = 0;
40 virtual void setColor(
double color_r,
double color_g,
double color_b,
double color_a = 1.0) = 0;
41 virtual visualization_msgs::Marker
getMarker() = 0;
42 virtual void updatePose(
const geometry_msgs::Vector3& pos,
const geometry_msgs::Quaternion& quat) = 0;
56 this->drawable_ = can_be_drawn;
virtual void setColor(double color_r, double color_g, double color_b, double color_a=1.0)=0
visualization_msgs::Marker marker_
virtual geometry_msgs::Pose getMarkerPose() const =0
std::shared_ptr< IMarkerShape > PtrIMarkerShape_t
virtual void updatePose(const geometry_msgs::Vector3 &pos, const geometry_msgs::Quaternion &quat)=0
fcl::BVHModel< fcl::RSS > BVH_RSS_t
virtual geometry_msgs::Pose getOriginRelToFrame() const =0
virtual uint32_t getId() const =0
static uint32_t class_ctr_
geometry_msgs::Pose origin_
void setDrawable(bool can_be_drawn)
IMarkerShape()
If the marker shape is even drawable or not.
Interface class marking methods that have to be implemented in derived classes.
virtual fcl::CollisionObject getCollisionObject() const =0
virtual visualization_msgs::Marker getMarker()=0