Public Types | Public Member Functions | Static Public Member Functions | Protected Attributes
jsk_footstep_planner::FootstepState Class Reference

#include <footstep_state.h>

List of all members.

Public Types

typedef boost::shared_ptr
< FootstepState
Ptr

Public Member Functions

pcl::PointIndices::Ptr cropPointCloud (pcl::PointCloud< pcl::PointNormal >::Ptr cloud, pcl::search::Octree< pcl::PointNormal > &tree)
pcl::PointIndices::Ptr cropPointCloud (pcl::PointCloud< pcl::PointNormal >::Ptr cloud, ANNGrid::Ptr grid_search)
pcl::PointIndices::Ptr cropPointCloudExact (pcl::PointCloud< pcl::PointNormal >::Ptr cloud, pcl::PointIndices::Ptr near_indices)
float cross2d (const Eigen::Vector2f &a, const Eigen::Vector2f &b) const
virtual bool crossCheck (FootstepState::Ptr other)
 return true if this and other are collision free.
 FootstepState (int leg, const Eigen::Affine3f &pose, const Eigen::Vector3f &dimensions, const Eigen::Vector3f &resolution)
 FootstepState (int leg, const Eigen::Affine3f &pose, const Eigen::Vector3f &dimensions, const Eigen::Vector3f &resolution, int index_x, int index_y, int index_yaw)
virtual Eigen::Vector3f getDimensions ()
virtual int getLeg ()
virtual Eigen::Affine3f getPose ()
virtual Eigen::Vector3f getResolution ()
virtual int indexT ()
virtual int indexX ()
virtual int indexY ()
virtual FootstepSupportState isSupportedByPointCloud (const Eigen::Affine3f &pose, pcl::PointCloud< pcl::PointNormal >::Ptr cloud, pcl::KdTreeFLANN< pcl::PointNormal > &tree, pcl::PointIndices::Ptr inliers, const int foot_x_sampling_num, const int foot_y_sampling_num, const double vertex_threshold)
virtual FootstepSupportState isSupportedByPointCloudWithoutCropping (const Eigen::Affine3f &pose, pcl::PointCloud< pcl::PointNormal >::Ptr cloud, pcl::KdTreeFLANN< pcl::PointNormal > &tree, pcl::PointIndices::Ptr inliers, const int foot_x_sampling_num, const int foot_y_sampling_num, const double vertex_threshold)
bool operator== (FootstepState &other)
virtual FootstepState::Ptr projectToCloud (pcl::KdTreeFLANN< pcl::PointNormal > &tree, pcl::PointCloud< pcl::PointNormal >::Ptr cloud, ANNGrid::Ptr grid_search, pcl::search::Octree< pcl::PointNormal > &tree_2d, pcl::PointCloud< pcl::PointNormal >::Ptr cloud_2d, const Eigen::Vector3f &z, unsigned int &error_state, double outlier_threshold, int max_iterations, int min_inliers, int foot_x_sampling_num=3, int foot_y_sampling_num=3, double vertex_threshold=0.02, const bool skip_cropping=true)
virtual void setPose (const Eigen::Affine3f &pose)
template<class PointT >
PointT toPoint ()
virtual
jsk_footstep_msgs::Footstep::Ptr 
toROSMsg ()
void vertices (Eigen::Vector3f &a, Eigen::Vector3f &b, Eigen::Vector3f &c, Eigen::Vector3f &d)

Static Public Member Functions

static FootstepState::Ptr fromROSMsg (const jsk_footstep_msgs::Footstep &f, const Eigen::Vector3f &size, const Eigen::Vector3f &resolution)

Protected Attributes

const Eigen::Vector3f dimensions_
int index_x_
int index_y_
int index_yaw_
const int leg_
Eigen::Affine3f pose_
const Eigen::Vector3f resolution_

Detailed Description

Definition at line 77 of file footstep_state.h.


Member Typedef Documentation

Definition at line 80 of file footstep_state.h.


Constructor & Destructor Documentation

jsk_footstep_planner::FootstepState::FootstepState ( int  leg,
const Eigen::Affine3f &  pose,
const Eigen::Vector3f &  dimensions,
const Eigen::Vector3f &  resolution 
) [inline]

Definition at line 81 of file footstep_state.h.

jsk_footstep_planner::FootstepState::FootstepState ( int  leg,
const Eigen::Affine3f &  pose,
const Eigen::Vector3f &  dimensions,
const Eigen::Vector3f &  resolution,
int  index_x,
int  index_y,
int  index_yaw 
) [inline]

Definition at line 96 of file footstep_state.h.


Member Function Documentation

pcl::PointIndices::Ptr jsk_footstep_planner::FootstepState::cropPointCloud ( pcl::PointCloud< pcl::PointNormal >::Ptr  cloud,
pcl::search::Octree< pcl::PointNormal > &  tree 
)

Definition at line 140 of file footstep_state.cpp.

pcl::PointIndices::Ptr jsk_footstep_planner::FootstepState::cropPointCloud ( pcl::PointCloud< pcl::PointNormal >::Ptr  cloud,
ANNGrid::Ptr  grid_search 
)

Definition at line 127 of file footstep_state.cpp.

pcl::PointIndices::Ptr jsk_footstep_planner::FootstepState::cropPointCloudExact ( pcl::PointCloud< pcl::PointNormal >::Ptr  cloud,
pcl::PointIndices::Ptr  near_indices 
)

Definition at line 85 of file footstep_state.cpp.

float jsk_footstep_planner::FootstepState::cross2d ( const Eigen::Vector2f &  a,
const Eigen::Vector2f &  b 
) const [inline]

Definition at line 113 of file footstep_state.h.

return true if this and other are collision free.

Definition at line 153 of file footstep_state.cpp.

FootstepState::Ptr jsk_footstep_planner::FootstepState::fromROSMsg ( const jsk_footstep_msgs::Footstep &  f,
const Eigen::Vector3f &  size,
const Eigen::Vector3f &  resolution 
) [static]

Definition at line 425 of file footstep_state.cpp.

virtual Eigen::Vector3f jsk_footstep_planner::FootstepState::getDimensions ( ) [inline, virtual]

Definition at line 182 of file footstep_state.h.

virtual int jsk_footstep_planner::FootstepState::getLeg ( ) [inline, virtual]

Definition at line 181 of file footstep_state.h.

virtual Eigen::Affine3f jsk_footstep_planner::FootstepState::getPose ( ) [inline, virtual]

Definition at line 175 of file footstep_state.h.

virtual Eigen::Vector3f jsk_footstep_planner::FootstepState::getResolution ( ) [inline, virtual]

Definition at line 190 of file footstep_state.h.

virtual int jsk_footstep_planner::FootstepState::indexT ( ) [inline, virtual]

Definition at line 195 of file footstep_state.h.

virtual int jsk_footstep_planner::FootstepState::indexX ( ) [inline, virtual]

Definition at line 193 of file footstep_state.h.

virtual int jsk_footstep_planner::FootstepState::indexY ( ) [inline, virtual]

Definition at line 194 of file footstep_state.h.

FootstepSupportState jsk_footstep_planner::FootstepState::isSupportedByPointCloud ( const Eigen::Affine3f &  pose,
pcl::PointCloud< pcl::PointNormal >::Ptr  cloud,
pcl::KdTreeFLANN< pcl::PointNormal > &  tree,
pcl::PointIndices::Ptr  inliers,
const int  foot_x_sampling_num,
const int  foot_y_sampling_num,
const double  vertex_threshold 
) [virtual]

Definition at line 301 of file footstep_state.cpp.

FootstepSupportState jsk_footstep_planner::FootstepState::isSupportedByPointCloudWithoutCropping ( const Eigen::Affine3f &  pose,
pcl::PointCloud< pcl::PointNormal >::Ptr  cloud,
pcl::KdTreeFLANN< pcl::PointNormal > &  tree,
pcl::PointIndices::Ptr  inliers,
const int  foot_x_sampling_num,
const int  foot_y_sampling_num,
const double  vertex_threshold 
) [virtual]

Definition at line 372 of file footstep_state.cpp.

bool jsk_footstep_planner::FootstepState::operator== ( FootstepState other) [inline]

Definition at line 183 of file footstep_state.h.

FootstepState::Ptr jsk_footstep_planner::FootstepState::projectToCloud ( pcl::KdTreeFLANN< pcl::PointNormal > &  tree,
pcl::PointCloud< pcl::PointNormal >::Ptr  cloud,
ANNGrid::Ptr  grid_search,
pcl::search::Octree< pcl::PointNormal > &  tree_2d,
pcl::PointCloud< pcl::PointNormal >::Ptr  cloud_2d,
const Eigen::Vector3f &  z,
unsigned int &  error_state,
double  outlier_threshold,
int  max_iterations,
int  min_inliers,
int  foot_x_sampling_num = 3,
int  foot_y_sampling_num = 3,
double  vertex_threshold = 0.02,
const bool  skip_cropping = true 
) [virtual]

Definition at line 180 of file footstep_state.cpp.

virtual void jsk_footstep_planner::FootstepState::setPose ( const Eigen::Affine3f &  pose) [inline, virtual]

Definition at line 176 of file footstep_state.h.

template<class PointT >
PointT jsk_footstep_planner::FootstepState::toPoint ( ) [inline]

Definition at line 147 of file footstep_state.h.

jsk_footstep_msgs::Footstep::Ptr jsk_footstep_planner::FootstepState::toROSMsg ( ) [virtual]

Definition at line 73 of file footstep_state.cpp.

void jsk_footstep_planner::FootstepState::vertices ( Eigen::Vector3f &  a,
Eigen::Vector3f &  b,
Eigen::Vector3f &  c,
Eigen::Vector3f &  d 
) [inline]

Definition at line 154 of file footstep_state.h.


Member Data Documentation

const Eigen::Vector3f jsk_footstep_planner::FootstepState::dimensions_ [protected]

Definition at line 217 of file footstep_state.h.

Definition at line 220 of file footstep_state.h.

Definition at line 221 of file footstep_state.h.

Definition at line 222 of file footstep_state.h.

Definition at line 219 of file footstep_state.h.

Eigen::Affine3f jsk_footstep_planner::FootstepState::pose_ [protected]

Definition at line 216 of file footstep_state.h.

const Eigen::Vector3f jsk_footstep_planner::FootstepState::resolution_ [protected]

Definition at line 218 of file footstep_state.h.


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


jsk_footstep_planner
Author(s): Ryohei Ueda
autogenerated on Wed Sep 16 2015 04:37:57