Public Member Functions | Static Public Member Functions | Protected Member Functions | Static Protected Member Functions | Private Types | Private Attributes
StrColRoSeService Class Reference

#include <StrColRoSeService.h>

List of all members.

Public Member Functions

virtual void finish ()
 StrColRoSeService (const RoSe::SID &sid)
virtual ~StrColRoSeService ()

Static Public Member Functions

static Service::Ptr create (const RoSe::SID &sid)

Protected Member Functions

void blackboardReadRun ()
bool connectBlackboard ()
void execute ()
void initialize ()
void readBlackboard ()
void receiveMsg (const RoSe::SID &, const RoSe::Message::Ptr)
void sendPlanes (const Planes &planes)
void sendPoints (RosePointcloudPtr pointCloud)
void stop ()
void terminate ()

Static Protected Member Functions

static void convertPoint (Point3f &outPointRoSe, const Vec3 &inPointEigen)
static void convertPoints (Points3f &brVertices, const EigenPoints &points)
static void encodeHeightmap (std::vector< unsigned char > &encodedHeightmap, const cv::Mat &heightmap, float widthRatio, float heightRatio)
static void encodeTexturemap (std::vector< unsigned char > &encodedTexturemap, std::vector< bool > &alphamap, const cv::Mat &texturemap, float widthRatio, float heightRatio)
static void extractUnmappedPointsToRosePC (RosePointcloudPtr unsegmentedPoints, PointCloudPtr mLastPointCloud, PlanePtrs pointMapping)
static void generateAlphamap (std::vector< bool > &alphamap, const cv::Mat &tempMat)

Private Types

typedef
StructureColoring::CylinderPatchVector 
CylinderPtrs
typedef
StructureColoring::CylinderPatches 
Cylinders
typedef std::vector< Vec3,
Eigen::aligned_allocator< Vec3 > > 
EigenPoints
typedef boost::scoped_ptr
< boost::thread > 
MyThreadPtr
typedef
StructureColoring::PlanePatchVector 
PlanePtrs
typedef
StructureColoring::PlanePatches 
Planes
typedef RoSe::PointT< float, 3 > Point3f
typedef RoSe::PointT< float,
3, RoSe::Color8 > 
Point3fc
typedef pcl::PointCloud< PointTPointCloud
typedef boost::shared_ptr
< const PointCloud
PointCloudConstPtr
typedef boost::shared_ptr
< PointCloud
PointCloudPtr
typedef std::vector< Point3fPoints3f
typedef pcl::PointXYZRGB PointT
typedef RoSe::PointCloud
< Point3fc, RoSe::Quaternion > 
RosePointcloud
typedef RoSe::PointCloud
< Point3fc, RoSe::Quaternion >
::Points 
RoSePointCloudPoints
typedef boost::shared_ptr
< RosePointcloud
RosePointcloudPtr
typedef Eigen::Vector3f Vec3

Private Attributes

MyThreadPtr mBBThread
RoSe::Condition mCondition
PointCloudPtr mLastPointCloud
RoSe::Mutex mMutex
ros::NodeHandle mNH
RoSe::Blackboard mPCBlackboard
RoSe::SID mPointcloudBlackboardSenderSID
RoSe::SID mSegmentedPlanesAndPointsRecieverSID
StructureColoring mStrCol

Detailed Description

Definition at line 60 of file StrColRoSeService.h.


Member Typedef Documentation

Definition at line 81 of file StrColRoSeService.h.

Definition at line 82 of file StrColRoSeService.h.

typedef std::vector<Vec3, Eigen::aligned_allocator<Vec3> > StrColRoSeService::EigenPoints [private]

Definition at line 64 of file StrColRoSeService.h.

typedef boost::scoped_ptr<boost::thread> StrColRoSeService::MyThreadPtr [private]

Definition at line 84 of file StrColRoSeService.h.

Definition at line 79 of file StrColRoSeService.h.

Definition at line 80 of file StrColRoSeService.h.

typedef RoSe::PointT<float, 3> StrColRoSeService::Point3f [private]

Definition at line 76 of file StrColRoSeService.h.

typedef RoSe::PointT<float, 3, RoSe::Color8> StrColRoSeService::Point3fc [private]

Definition at line 71 of file StrColRoSeService.h.

Definition at line 67 of file StrColRoSeService.h.

typedef boost::shared_ptr<const PointCloud> StrColRoSeService::PointCloudConstPtr [private]

Definition at line 69 of file StrColRoSeService.h.

typedef boost::shared_ptr<PointCloud> StrColRoSeService::PointCloudPtr [private]

Definition at line 68 of file StrColRoSeService.h.

typedef std::vector<Point3f> StrColRoSeService::Points3f [private]

Definition at line 77 of file StrColRoSeService.h.

typedef pcl::PointXYZRGB StrColRoSeService::PointT [private]

Definition at line 66 of file StrColRoSeService.h.

typedef RoSe::PointCloud<Point3fc, RoSe::Quaternion> StrColRoSeService::RosePointcloud [private]

Definition at line 72 of file StrColRoSeService.h.

typedef RoSe::PointCloud<Point3fc, RoSe::Quaternion>::Points StrColRoSeService::RoSePointCloudPoints [private]

Definition at line 73 of file StrColRoSeService.h.

typedef boost::shared_ptr<RosePointcloud> StrColRoSeService::RosePointcloudPtr [private]

Definition at line 74 of file StrColRoSeService.h.

typedef Eigen::Vector3f StrColRoSeService::Vec3 [private]

Definition at line 63 of file StrColRoSeService.h.


Constructor & Destructor Documentation

StrColRoSeService::StrColRoSeService ( const RoSe::SID &  sid)

Creates a new rosconnectorServer service. A service class must have a constructor with the same parameter list. It is needed for the Service.cmdLine() method.

Parameters:
sidthe sid of this service

Definition at line 49 of file StrColRoSeService.cpp.

Definition at line 55 of file StrColRoSeService.cpp.


Member Function Documentation

Definition at line 381 of file StrColRoSeService.cpp.

Definition at line 322 of file StrColRoSeService.cpp.

void StrColRoSeService::convertPoint ( Point3f outPointRoSe,
const Vec3 inPointEigen 
) [inline, static, protected]

Definition at line 146 of file StrColRoSeService.h.

void StrColRoSeService::convertPoints ( Points3f brVertices,
const EigenPoints points 
) [inline, static, protected]

Definition at line 154 of file StrColRoSeService.h.

RoSe::Service::Ptr StrColRoSeService::create ( const RoSe::SID &  sid) [static]

Creates a new service of the specified type;

Definition at line 43 of file StrColRoSeService.cpp.

void StrColRoSeService::encodeHeightmap ( std::vector< unsigned char > &  encodedHeightmap,
const cv::Mat &  heightmap,
float  widthRatio,
float  heightRatio 
) [static, protected]

Definition at line 227 of file StrColRoSeService.cpp.

void StrColRoSeService::encodeTexturemap ( std::vector< unsigned char > &  encodedTexturemap,
std::vector< bool > &  alphamap,
const cv::Mat &  texturemap,
float  widthRatio,
float  heightRatio 
) [static, protected]

Definition at line 254 of file StrColRoSeService.cpp.

void StrColRoSeService::execute ( ) [protected]

Definition at line 73 of file StrColRoSeService.cpp.

void StrColRoSeService::extractUnmappedPointsToRosePC ( RosePointcloudPtr  unsegmentedPoints,
PointCloudPtr  mLastPointCloud,
PlanePtrs  pointMapping 
) [static, protected]

Definition at line 196 of file StrColRoSeService.cpp.

void StrColRoSeService::finish ( ) [virtual]

Definition at line 65 of file StrColRoSeService.cpp.

void StrColRoSeService::generateAlphamap ( std::vector< bool > &  alphamap,
const cv::Mat &  tempMat 
) [static, protected]

Definition at line 242 of file StrColRoSeService.cpp.

void StrColRoSeService::initialize ( ) [protected]

Definition at line 102 of file StrColRoSeService.cpp.

void StrColRoSeService::readBlackboard ( ) [protected]

Definition at line 337 of file StrColRoSeService.cpp.

void StrColRoSeService::receiveMsg ( const RoSe::SID &  ,
const RoSe::Message::Ptr   
) [protected]

Definition at line 191 of file StrColRoSeService.cpp.

void StrColRoSeService::sendPlanes ( const Planes planes) [protected]

Definition at line 270 of file StrColRoSeService.cpp.

void StrColRoSeService::sendPoints ( RosePointcloudPtr  pointCloud) [protected]

Definition at line 296 of file StrColRoSeService.cpp.

void StrColRoSeService::stop ( ) [protected]
void StrColRoSeService::terminate ( ) [protected]

Definition at line 61 of file StrColRoSeService.cpp.


Member Data Documentation

Definition at line 95 of file StrColRoSeService.h.

RoSe::Condition StrColRoSeService::mCondition [private]

Definition at line 93 of file StrColRoSeService.h.

Definition at line 97 of file StrColRoSeService.h.

RoSe::Mutex StrColRoSeService::mMutex [private]

Definition at line 92 of file StrColRoSeService.h.

ros::NodeHandle StrColRoSeService::mNH [private]

Definition at line 87 of file StrColRoSeService.h.

RoSe::Blackboard StrColRoSeService::mPCBlackboard [private]

Definition at line 94 of file StrColRoSeService.h.

Definition at line 89 of file StrColRoSeService.h.

Definition at line 90 of file StrColRoSeService.h.

Definition at line 100 of file StrColRoSeService.h.


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


structure_coloring_fkie
Author(s): Bastian Gaspers
autogenerated on Sun Jan 5 2014 11:38:09