Public Member Functions | Private Member Functions | Private Attributes
MarkerShape< T > Class Template Reference

Template class implementation for box, sphere and cylinder fcl::shapes. Creates visualization marker. More...

#include <marker_shapes.hpp>

Inheritance diagram for MarkerShape< T >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

fcl::CollisionObject getCollisionObject () const
uint32_t getId () const
visualization_msgs::Marker getMarker ()
geometry_msgs::Pose getMarkerPose () const
geometry_msgs::Pose getOriginRelToFrame () const
 MarkerShape (const std::string &root_frame, T &fcl_object, const geometry_msgs::Pose &pose, const std_msgs::ColorRGBA &col)
 MarkerShape (const std::string &root_frame, T &fcl_object, const geometry_msgs::Point &pos, const geometry_msgs::Quaternion &quat, const std_msgs::ColorRGBA &col)
 MarkerShape (const std::string &root_frame, T &fcl_object, double x, double y, double z, double quat_x=0.0, double quat_y=0.0, double quat_z=0.0, double quat_w=1.0, double color_r=0.0, double color_g=0.0, double color_b=0.0, double color_a=1.0)
 MarkerShape (const std::string &root_frame, double x, double y, double z, double quat_x=0.0, double quat_y=0.0, double quat_z=0.0, double quat_w=1.0, double color_r=0.0, double color_g=0.0, double color_b=0.0, double color_a=1.0)
void setColor (double color_r, double color_g, double color_b, double color_a=1.0)
void updatePose (const geometry_msgs::Vector3 &pos, const geometry_msgs::Quaternion &quat)
void updatePose (const geometry_msgs::Pose &pose)
virtual ~MarkerShape ()

Private Member Functions

void init (const std::string &root_frame, double x, double y, double z, double quat_x, double quat_y, double quat_z, double quat_w, double color_r, double color_g, double color_b, double color_a)

Private Attributes

FclMarkerConverter< Tfcl_marker_converter_
boost::shared_ptr< BVH_RSS_tptr_fcl_bvh_

Detailed Description

template<typename T>
class MarkerShape< T >

Template class implementation for box, sphere and cylinder fcl::shapes. Creates visualization marker.

Definition at line 41 of file marker_shapes.hpp.


Constructor & Destructor Documentation

template<typename T >
MarkerShape< T >::MarkerShape ( const std::string &  root_frame,
T fcl_object,
const geometry_msgs::Pose pose,
const std_msgs::ColorRGBA &  col 
) [inline]

Definition at line 52 of file marker_shapes.hpp.

template<typename T >
MarkerShape< T >::MarkerShape ( const std::string &  root_frame,
T fcl_object,
const geometry_msgs::Point pos,
const geometry_msgs::Quaternion &  quat,
const std_msgs::ColorRGBA &  col 
) [inline]

Definition at line 60 of file marker_shapes.hpp.

template<typename T >
MarkerShape< T >::MarkerShape ( const std::string &  root_frame,
T fcl_object,
double  x,
double  y,
double  z,
double  quat_x = 0.0,
double  quat_y = 0.0,
double  quat_z = 0.0,
double  quat_w = 1.0,
double  color_r = 0.0,
double  color_g = 0.0,
double  color_b = 0.0,
double  color_a = 1.0 
)

Definition at line 25 of file marker_shapes_impl.hpp.

template<typename T >
MarkerShape< T >::MarkerShape ( const std::string &  root_frame,
double  x,
double  y,
double  z,
double  quat_x = 0.0,
double  quat_y = 0.0,
double  quat_z = 0.0,
double  quat_w = 1.0,
double  color_r = 0.0,
double  color_g = 0.0,
double  color_b = 0.0,
double  color_a = 1.0 
)

Definition at line 35 of file marker_shapes_impl.hpp.

template<typename T >
virtual MarkerShape< T >::~MarkerShape ( ) [inline, virtual]

Definition at line 99 of file marker_shapes.hpp.


Member Function Documentation

template<typename T >
fcl::CollisionObject MarkerShape< T >::getCollisionObject ( ) const [virtual]
Returns:
A fcl::CollisionObject to calculate distances to other objects or check whether collision occurred or not.

Implements IMarkerShape.

Definition at line 118 of file marker_shapes_impl.hpp.

template<typename T >
uint32_t MarkerShape< T >::getId ( ) const [inline, virtual]
Parameters:
Returnsthe marker id with that it is published to RVIZ.

Implements IMarkerShape.

Definition at line 92 of file marker_shapes_impl.hpp.

template<typename T >
visualization_msgs::Marker MarkerShape< T >::getMarker ( ) [inline, virtual]
Returns:
Gets the visualization marker of this MarkerShape.

Implements IMarkerShape.

Definition at line 110 of file marker_shapes_impl.hpp.

template<typename T >
geometry_msgs::Pose MarkerShape< T >::getMarkerPose ( ) const [inline, virtual]

Implements IMarkerShape.

Definition at line 43 of file marker_shapes_impl.hpp.

template<typename T >
geometry_msgs::Pose MarkerShape< T >::getOriginRelToFrame ( ) const [inline, virtual]

Implements IMarkerShape.

Definition at line 50 of file marker_shapes_impl.hpp.

template<typename T >
void MarkerShape< T >::init ( const std::string &  root_frame,
double  x,
double  y,
double  z,
double  quat_x,
double  quat_y,
double  quat_z,
double  quat_w,
double  color_r,
double  color_g,
double  color_b,
double  color_a 
) [private]

Definition at line 57 of file marker_shapes_impl.hpp.

template<typename T >
void MarkerShape< T >::setColor ( double  color_r,
double  color_g,
double  color_b,
double  color_a = 1.0 
) [inline, virtual]

Implements IMarkerShape.

Definition at line 99 of file marker_shapes_impl.hpp.

template<typename T >
void MarkerShape< T >::updatePose ( const geometry_msgs::Vector3 pos,
const geometry_msgs::Quaternion &  quat 
) [inline, virtual]

Implements IMarkerShape.

Definition at line 133 of file marker_shapes_impl.hpp.

template<typename T >
void MarkerShape< T >::updatePose ( const geometry_msgs::Pose pose) [inline, virtual]

Implements IMarkerShape.

Definition at line 143 of file marker_shapes_impl.hpp.


Member Data Documentation

template<typename T >
FclMarkerConverter<T> MarkerShape< T >::fcl_marker_converter_ [private]

Definition at line 44 of file marker_shapes.hpp.

template<typename T >
boost::shared_ptr<BVH_RSS_t> MarkerShape< T >::ptr_fcl_bvh_ [private]

Definition at line 45 of file marker_shapes.hpp.


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


cob_obstacle_distance
Author(s): Marco Bezzon
autogenerated on Thu Jun 6 2019 21:19:14