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

#include <marker_shapes.hpp>

Inheritance diagram for MarkerShape< BVH_RSS_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, const shape_msgs::Mesh &mesh, const geometry_msgs::Pose &pose, const std_msgs::ColorRGBA &col)
 MarkerShape (const std::string &root_frame, const std::string &mesh_resource, const geometry_msgs::Pose &pose, const std_msgs::ColorRGBA &col)
 MarkerShape (const std::string &root_frame, const std::string &mesh_resource, const geometry_msgs::Point &pos, const geometry_msgs::Quaternion &quat, const std_msgs::ColorRGBA &col)
 MarkerShape (const std::string &root_frame, const std::string &mesh_resource, 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, const std::string &mesh_resource, 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

boost::shared_ptr< BVH_RSS_tptr_fcl_bvh_

Detailed Description

template<>
class MarkerShape< BVH_RSS_t >

Definition at line 107 of file marker_shapes.hpp.


Constructor & Destructor Documentation

MarkerShape< BVH_RSS_t >::MarkerShape ( const std::string &  root_frame,
const shape_msgs::Mesh &  mesh,
const geometry_msgs::Pose pose,
const std_msgs::ColorRGBA &  col 
)

Definition at line 24 of file marker_shapes_impl.cpp.

MarkerShape< BVH_RSS_t >::MarkerShape ( const std::string &  root_frame,
const std::string &  mesh_resource,
const geometry_msgs::Pose pose,
const std_msgs::ColorRGBA &  col 
) [inline]

Definition at line 119 of file marker_shapes.hpp.

MarkerShape< BVH_RSS_t >::MarkerShape ( const std::string &  root_frame,
const std::string &  mesh_resource,
const geometry_msgs::Point pos,
const geometry_msgs::Quaternion &  quat,
const std_msgs::ColorRGBA &  col 
) [inline]

Definition at line 127 of file marker_shapes.hpp.

MarkerShape< BVH_RSS_t >::MarkerShape ( const std::string &  root_frame,
const std::string &  mesh_resource,
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 66 of file marker_shapes_impl.cpp.

virtual MarkerShape< BVH_RSS_t >::~MarkerShape ( ) [inline, virtual]

Definition at line 162 of file marker_shapes.hpp.


Member Function Documentation

fcl::CollisionObject MarkerShape< BVH_RSS_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 166 of file marker_shapes_impl.cpp.

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

Implements IMarkerShape.

Definition at line 129 of file marker_shapes_impl.cpp.

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

Implements IMarkerShape.

Definition at line 159 of file marker_shapes_impl.cpp.

geometry_msgs::Pose MarkerShape< BVH_RSS_t >::getMarkerPose ( ) const [inline, virtual]

Implements IMarkerShape.

Definition at line 117 of file marker_shapes_impl.cpp.

Implements IMarkerShape.

Definition at line 123 of file marker_shapes_impl.cpp.

void MarkerShape< BVH_RSS_t >::init ( const std::string &  root_frame,
const std::string &  mesh_resource,
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 75 of file marker_shapes_impl.cpp.

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

Implements IMarkerShape.

Definition at line 135 of file marker_shapes_impl.cpp.

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

Implements IMarkerShape.

Definition at line 144 of file marker_shapes_impl.cpp.

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

Implements IMarkerShape.

Definition at line 153 of file marker_shapes_impl.cpp.


Member Data Documentation

boost::shared_ptr<BVH_RSS_t> MarkerShape< BVH_RSS_t >::ptr_fcl_bvh_ [private]

Definition at line 110 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