Public Member Functions | Protected Attributes | Static Protected Attributes | List of all members
IMarkerShape Class Referenceabstract

Interface class marking methods that have to be implemented in derived classes. More...

#include <marker_shapes_interface.hpp>

Inheritance diagram for IMarkerShape:
Inheritance graph
[legend]

Public Member Functions

virtual fcl::CollisionObject getCollisionObject () const =0
 
virtual uint32_t getId () const =0
 
virtual visualization_msgs::Marker getMarker ()=0
 
virtual geometry_msgs::Pose getMarkerPose () const =0
 
virtual geometry_msgs::Pose getOriginRelToFrame () const =0
 
 IMarkerShape ()
 

If the marker shape is even drawable or not.

More...
 
bool isDrawable ()
 
virtual void setColor (double color_r, double color_g, double color_b, double color_a=1.0)=0
 
void setDrawable (bool can_be_drawn)
 
virtual void updatePose (const geometry_msgs::Vector3 &pos, const geometry_msgs::Quaternion &quat)=0
 
virtual void updatePose (const geometry_msgs::Pose &pose)=0
 
virtual ~IMarkerShape ()
 

Protected Attributes

bool drawable_
 
visualization_msgs::Marker marker_
 
geometry_msgs::Pose origin_
 

Static Protected Attributes

static uint32_t class_ctr_ = 0
 

Detailed Description

Interface class marking methods that have to be implemented in derived classes.

Definition at line 29 of file marker_shapes_interface.hpp.

Constructor & Destructor Documentation

IMarkerShape::IMarkerShape ( )

If the marker shape is even drawable or not.

Interface class marking methods that have to be implemented in derived classes.

Definition at line 22 of file marker_shapes_interface.cpp.

virtual IMarkerShape::~IMarkerShape ( )
inlinevirtual

Definition at line 64 of file marker_shapes_interface.hpp.

Member Function Documentation

virtual fcl::CollisionObject IMarkerShape::getCollisionObject ( ) const
pure virtual
virtual uint32_t IMarkerShape::getId ( ) const
pure virtual
virtual visualization_msgs::Marker IMarkerShape::getMarker ( )
pure virtual
virtual geometry_msgs::Pose IMarkerShape::getMarkerPose ( ) const
pure virtual
virtual geometry_msgs::Pose IMarkerShape::getOriginRelToFrame ( ) const
pure virtual
bool IMarkerShape::isDrawable ( )
inline

Definition at line 59 of file marker_shapes_interface.hpp.

virtual void IMarkerShape::setColor ( double  color_r,
double  color_g,
double  color_b,
double  color_a = 1.0 
)
pure virtual
void IMarkerShape::setDrawable ( bool  can_be_drawn)
inline

Decide whether the marker shape can be drawn or not. E.g. self collision frames need not to be drawn again as they are available in rviz -> robot model -> collision enabled.

Parameters
can_be_drawnDecide whether the marker shall be drawn or not.

Definition at line 54 of file marker_shapes_interface.hpp.

virtual void IMarkerShape::updatePose ( const geometry_msgs::Vector3 pos,
const geometry_msgs::Quaternion &  quat 
)
pure virtual
virtual void IMarkerShape::updatePose ( const geometry_msgs::Pose pose)
pure virtual

Member Data Documentation

uint32_t IMarkerShape::class_ctr_ = 0
staticprotected

Definition at line 32 of file marker_shapes_interface.hpp.

bool IMarkerShape::drawable_
protected

Definition at line 35 of file marker_shapes_interface.hpp.

visualization_msgs::Marker IMarkerShape::marker_
protected

Definition at line 33 of file marker_shapes_interface.hpp.

geometry_msgs::Pose IMarkerShape::origin_
protected

Definition at line 34 of file marker_shapes_interface.hpp.


The documentation for this class was generated from the following files:


cob_obstacle_distance
Author(s): Marco Bezzon
autogenerated on Thu Apr 8 2021 02:39:47