Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
plane_model_road< T > Class Template Reference

#include <plane_model_road_segmentation.h>

Public Member Functions

tf::Transform find_and_publish_road_frame (pcl::PointCloud< T > cloud_in)
 get and publish the road frame T his f*unction does all the work for you. here are the main steps: STEP 1 create the model coeeficients STEP 2 project origin to plane, for example STEP 3 Find the difference between the cloud frame_id to ground STEP 4 Calculate the difference z axis STEP 5 Publish the road frame More...
 
tf::Transform find_and_publish_road_frame (const sensor_msgs::PointCloud2ConstPtr &msg)
 overload function for ros msgs Converts sensor_msgs::PointCloud2 to pcl and calls the function find_and_publish_road_frame(pcl::PointCloud< T> pc) More...
 
bool find_road_frame (pcl::PointCloud< T > cloud_in)
 get the road reference frame More...
 
bool find_road_frame (const sensor_msgs::PointCloud2ConstPtr &msg)
 overload function for ros msgs Converts sensor_msgs::PointCloud2 to pcl and calls the function find_road_frame(pcl::PointCloud< T> pc) More...
 
pcl::PointCloud< T > get_plane_coefficients (pcl::PointCloud< T > cloud_in, int iterations, float threshold, pcl::ModelCoefficients::Ptr coefficients)
 Calculate plane coefficients It uses pcl RANSAC model to estimate the coeeficients of a plane. More...
 
 plane_model_road ()
 
 ~plane_model_road ()
 

Public Attributes

tf::TransformBroadcaster * broadcast_ptr
 
pcl::ModelCoefficients::Ptr coef
 
bool debug
 
int iterations
 
tf::TransformListener * listener_atc_ground_ptr
 
point_origin
 
point_x
 
point_y
 
std::string pub_frame_name
 
std::string reference_ground_frame
 
float threshold
 

Private Member Functions

bool check_distance (double distance, double threshold)
 check if distance matches with threshold If returned true, you probably get the road plane More...
 
vector< double > find_RP_angle (T origin_projected, T pt_x_projected, T pt_y_projected)
 find RP angles for road frame Gets the road frame RP angles. Notice that you don't need the Y. More...
 
tf::Transform get_transform (T origin_projected, T pt_x_projected, T pt_y_projected)
 get the transformation point Gets the road transform to publish More...
 
project_point_to_plane (const T ptin, const pcl::ModelCoefficients::Ptr coeff)
 Project a point on a plane It uses pcl projectinliers to project a point on a plane. More...
 
transform_pcl_point (std::string frame1, std::string frame2, T pt_origin)
 Transform a pcl point between two ros frames It uses a tf::Stamped transform to transform a point between reference frames. More...
 

Private Attributes

origin_projected
 
pcl::PointCloud< T > outliers
 
pt_x_projected
 
pt_y_projected
 

Detailed Description

template<class T>
class plane_model_road< T >

This is a class to detect the road reference frame

Date
March 2012
Author
ttalhada

Definition at line 72 of file plane_model_road_segmentation.h.

Constructor & Destructor Documentation

template<class T>
plane_model_road< T >::plane_model_road ( )
inline

Definition at line 148 of file plane_model_road_segmentation.h.

template<class T>
plane_model_road< T >::~plane_model_road ( )
inline

Definition at line 161 of file plane_model_road_segmentation.h.

Member Function Documentation

template<class T>
bool plane_model_road< T >::check_distance ( double  distance,
double  threshold 
)
inlineprivate

check if distance matches with threshold If returned true, you probably get the road plane

Parameters
[in]distance
[in]threshold
Returns
bool result

Definition at line 201 of file plane_model_road_segmentation.h.

template<class T >
tf::Transform plane_model_road< T >::find_and_publish_road_frame ( pcl::PointCloud< T >  cloud_in)

get and publish the road frame T his f*unction does all the work for you. here are the main steps: STEP 1 create the model coeeficients STEP 2 project origin to plane, for example STEP 3 Find the difference between the cloud frame_id to ground STEP 4 Calculate the difference z axis STEP 5 Publish the road frame

Parameters
[in]origin_projected
Returns
tf::Transform

Definition at line 107 of file plane_model_road_segmentation_implementation.hpp.

template<class T >
tf::Transform plane_model_road< T >::find_and_publish_road_frame ( const sensor_msgs::PointCloud2ConstPtr &  msg)

overload function for ros msgs Converts sensor_msgs::PointCloud2 to pcl and calls the function find_and_publish_road_frame(pcl::PointCloud< T> pc)

Parameters
[in]msg
Returns
transform

Definition at line 122 of file plane_model_road_segmentation_implementation.hpp.

template<class T >
bool plane_model_road< T >::find_road_frame ( pcl::PointCloud< T >  cloud_in)

get the road reference frame

T h*is function does all the work for you. here are the main steps: STEP 1 create the model coeeficients STEP 2 project origin to plane, for example STEP 3 Find the difference between the cloud frame_id to ground STEP 4 Calculate the difference z axis

Parameters
[in]cloud_in
Returns
bool success

Definition at line 62 of file plane_model_road_segmentation_implementation.hpp.

template<class T >
bool plane_model_road< T >::find_road_frame ( const sensor_msgs::PointCloud2ConstPtr &  msg)

overload function for ros msgs Converts sensor_msgs::PointCloud2 to pcl and calls the function find_road_frame(pcl::PointCloud< T> pc)

Parameters
[in]msg
Returns
success

Definition at line 94 of file plane_model_road_segmentation_implementation.hpp.

template<class T >
vector< double > plane_model_road< T >::find_RP_angle ( origin_projected,
pt_x_projected,
pt_y_projected 
)
private

find RP angles for road frame Gets the road frame RP angles. Notice that you don't need the Y.

Parameters
[in]origin_projected
[in]pt_x_projected
[in]pt_y_projected
Returns
std::vector< double> with R and P.

Definition at line 206 of file plane_model_road_segmentation_implementation.hpp.

template<class T >
pcl::PointCloud< T > plane_model_road< T >::get_plane_coefficients ( pcl::PointCloud< T >  cloud_in,
int  iterations,
float  threshold,
pcl::ModelCoefficients::Ptr  coefficients 
)

Calculate plane coefficients It uses pcl RANSAC model to estimate the coeeficients of a plane.

You may use after call yhis function: (to see Ax+By+Cz+D=0)

cout<< coeeficients.values<<endl;
Parameters
[in]*ptin
[in]iterations
[in]threshold
[out]coefficients
Returns
cloud out

Definition at line 131 of file plane_model_road_segmentation_implementation.hpp.

template<class T >
tf::Transform plane_model_road< T >::get_transform ( origin_projected,
pt_x_projected,
pt_y_projected 
)
private

get the transformation point Gets the road transform to publish

Parameters
[in]origin_projected
[in]pt_x_projected
[in]pt_y_projected
Returns
transform from a projected point

Definition at line 40 of file plane_model_road_segmentation_implementation.hpp.

template<class T >
T plane_model_road< T >::project_point_to_plane ( const T  ptin,
const pcl::ModelCoefficients::Ptr  coeff 
)
private

Project a point on a plane It uses pcl projectinliers to project a point on a plane.

Parameters
[in]*ptin
[in]coeff
Returns
*ptout

Definition at line 165 of file plane_model_road_segmentation_implementation.hpp.

template<class T >
T plane_model_road< T >::transform_pcl_point ( std::string  frame1,
std::string  frame2,
pt_origin 
)
private

Transform a pcl point between two ros frames It uses a tf::Stamped transform to transform a point between reference frames.

Parameters
[in]frame1
[in]frame2
[in]pt_origin
Returns
point_transformed

Definition at line 186 of file plane_model_road_segmentation_implementation.hpp.

Member Data Documentation

template<class T>
tf::TransformBroadcaster* plane_model_road< T >::broadcast_ptr

Definition at line 142 of file plane_model_road_segmentation.h.

template<class T>
pcl::ModelCoefficients::Ptr plane_model_road< T >::coef

Definition at line 145 of file plane_model_road_segmentation.h.

template<class T>
bool plane_model_road< T >::debug

Definition at line 137 of file plane_model_road_segmentation.h.

template<class T>
int plane_model_road< T >::iterations

Definition at line 136 of file plane_model_road_segmentation.h.

template<class T>
tf::TransformListener* plane_model_road< T >::listener_atc_ground_ptr

Definition at line 141 of file plane_model_road_segmentation.h.

template<class T>
T plane_model_road< T >::origin_projected
private

Definition at line 170 of file plane_model_road_segmentation.h.

template<class T>
pcl::PointCloud<T> plane_model_road< T >::outliers
private

Definition at line 164 of file plane_model_road_segmentation.h.

template<class T>
T plane_model_road< T >::point_origin

Definition at line 138 of file plane_model_road_segmentation.h.

template<class T>
T plane_model_road< T >::point_x

Definition at line 139 of file plane_model_road_segmentation.h.

template<class T>
T plane_model_road< T >::point_y

Definition at line 140 of file plane_model_road_segmentation.h.

template<class T>
T plane_model_road< T >::pt_x_projected
private

Definition at line 171 of file plane_model_road_segmentation.h.

template<class T>
T plane_model_road< T >::pt_y_projected
private

Definition at line 172 of file plane_model_road_segmentation.h.

template<class T>
std::string plane_model_road< T >::pub_frame_name

Definition at line 143 of file plane_model_road_segmentation.h.

template<class T>
std::string plane_model_road< T >::reference_ground_frame

Definition at line 144 of file plane_model_road_segmentation.h.

template<class T>
float plane_model_road< T >::threshold

Definition at line 135 of file plane_model_road_segmentation.h.


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


plane_model_road_segmentation
Author(s): Tiago Talhada
autogenerated on Mon Mar 2 2015 01:32:38