Public Member Functions | Private Attributes
rail::pick_and_place::PCLGraspModel Class Reference

A wrapper around a graspdb GrapsModel with a PCL point cloud. More...

#include <PCLGraspModel.h>

Inheritance diagram for rail::pick_and_place::PCLGraspModel:
Inheritance graph
[legend]

List of all members.

Public Member Functions

double getAverageBlue () const
 Average point cloud blue value accessor.
double getAverageGreen () const
 Average point cloud green value accessor.
double getAverageRed () const
 Average point cloud red value accessor.
const pcl::PointCloud
< pcl::PointXYZRGB >::Ptr & 
getPCLPointCloud () const
 PCL point cloud accessor.
const sensor_msgs::PointCloud2 & getPointCloud () const
 Disabled point cloud accessor (immutable).
sensor_msgs::PointCloud2 & getPointCloud ()
 Disabled point cloud accessor.
bool isOriginal () const
 Original flag accessor.
 PCLGraspModel (const graspdb::GraspModel &grasp_model=graspdb::GraspModel())
 Creates a new PCLGraspModel.
void setOriginal (const bool original)
 Original flag mutator.
void setPointCloud (const sensor_msgs::PointCloud2 &point_cloud)
 Point cloud mutator.
graspdb::GraspModel toGraspModel () const
 Creates a graspdb GraspModel from this PCL grasp model.

Private Attributes

double avg_b_
double avg_g_
double avg_r_
bool original_
pcl::PointCloud
< pcl::PointXYZRGB >::Ptr 
pc_

Detailed Description

A wrapper around a graspdb GrapsModel with a PCL point cloud.

The PCLGraspModel is simply a wrapper around the graspdb GrapsModel with a PCL point cloud. A flag can also be set to mark the grasp model as an original (as apposed to newly generated during model generation). All accessors to the ROS point cloud message are disabled.

Definition at line 36 of file PCLGraspModel.h.


Constructor & Destructor Documentation

Creates a new PCLGraspModel.

Creates a new ObjectRecognizer from the graspdb grasp model object. The point cloud is converted during construction. The original flag defaults to false.

Parameters:
grasp_modelThe graspdb GraspModel to create a PCLGraspModel from (defaults to an empty GraspModel).

Definition at line 20 of file PCLGraspModel.cpp.


Member Function Documentation

Average point cloud blue value accessor.

Get average point cloud blue value.

Returns:
The average point cloud blue value.

Definition at line 84 of file PCLGraspModel.cpp.

Average point cloud green value accessor.

Get average point cloud green value.

Returns:
The average point cloud green value.

Definition at line 79 of file PCLGraspModel.cpp.

double PCLGraspModel::getAverageRed ( ) const

Average point cloud red value accessor.

Get average point cloud red value.

Returns:
The average point cloud red value.

Definition at line 74 of file PCLGraspModel.cpp.

const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & PCLGraspModel::getPCLPointCloud ( ) const

PCL point cloud accessor.

Get the PCL point cloud.

Returns:
The PCL point cloud.

Definition at line 51 of file PCLGraspModel.cpp.

const sensor_msgs::PointCloud2 & PCLGraspModel::getPointCloud ( ) const

Disabled point cloud accessor (immutable).

Unavailable function.

Returns:
Nothing (exception will be thrown).
Exceptions:
std::runtime_errorThrown since this method is not supported.

Reimplemented from rail::pick_and_place::graspdb::GraspModel.

Definition at line 61 of file PCLGraspModel.cpp.

sensor_msgs::PointCloud2 & PCLGraspModel::getPointCloud ( )

Disabled point cloud accessor.

Unavailable function.

Returns:
Nothing (exception will be thrown).
Exceptions:
std::runtime_errorThrown since this method is not supported.

Reimplemented from rail::pick_and_place::graspdb::GraspModel.

Definition at line 56 of file PCLGraspModel.cpp.

bool PCLGraspModel::isOriginal ( ) const

Original flag accessor.

Gets the value of the original flag (defaults to false).

Returns:
The value of the original model flag.

Definition at line 41 of file PCLGraspModel.cpp.

void PCLGraspModel::setOriginal ( const bool  original)

Original flag mutator.

Sets the value of the original flag.

Parameters:
originalThe new value of the original model flag.

Definition at line 46 of file PCLGraspModel.cpp.

void PCLGraspModel::setPointCloud ( const sensor_msgs::PointCloud2 &  point_cloud)

Point cloud mutator.

Set the point cloud message to the given values based on the ROS message.

Parameters:
point_cloudThe ROS PointCloud2 message to store.

Reimplemented from rail::pick_and_place::graspdb::GraspModel.

Definition at line 66 of file PCLGraspModel.cpp.

Creates a graspdb GraspModel from this PCL grasp model.

Creates and returns a new graspdb GraspModel from this PCL grasp model.

Returns:
The new graspdb GraspModel.

Definition at line 89 of file PCLGraspModel.cpp.


Member Data Documentation

Definition at line 147 of file PCLGraspModel.h.

Definition at line 147 of file PCLGraspModel.h.

Color information for the point cloud

Definition at line 147 of file PCLGraspModel.h.

The original model flag.

Definition at line 143 of file PCLGraspModel.h.

The internal shared pointer to the PCL point cloud.

Definition at line 145 of file PCLGraspModel.h.


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


rail_recognition
Author(s): David Kent , Russell Toris , bhetherman
autogenerated on Sun Mar 6 2016 11:39:13