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, ANNGrid::Ptr grid_search, double padding_x=0.0, double padding_y=0.0)
pcl::PointIndices::Ptr cropPointCloudExact (pcl::PointCloud< pcl::PointNormal >::Ptr cloud, pcl::PointIndices::Ptr near_indices, double padding_x=0.0, double padding_y=0.0)
float cross2d (const Eigen::Vector2f &a, const Eigen::Vector2f &b) const
virtual bool crossCheck (FootstepState::Ptr other, float collision_padding=0)
 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 () const
virtual int getLeg () const
virtual Eigen::Affine3f getPose () const
virtual Eigen::Vector3f getResolution () const
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)
virtual Eigen::Affine3f midcoords (const FootstepState &other)
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, FootstepParameters &parameters)
virtual void setPose (const Eigen::Affine3f &pose)
template<class PointT >
PointT toPoint ()
virtual
jsk_footstep_msgs::Footstep::Ptr 
toROSMsg ()
virtual
jsk_footstep_msgs::Footstep::Ptr 
toROSMsg (const Eigen::Vector3f &ioffset)
void vertices (Eigen::Vector3f &a, Eigen::Vector3f &b, Eigen::Vector3f &c, Eigen::Vector3f &d, double collision_padding=0)

Static Public Member Functions

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

Protected Attributes

bool debug_print_
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 80 of file footstep_state.h.


Member Typedef Documentation

Definition at line 83 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 84 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 100 of file footstep_state.h.


Member Function Documentation

pcl::PointIndices::Ptr jsk_footstep_planner::FootstepState::cropPointCloud ( pcl::PointCloud< pcl::PointNormal >::Ptr  cloud,
ANNGrid::Ptr  grid_search,
double  padding_x = 0.0,
double  padding_y = 0.0 
)

Definition at line 155 of file footstep_state.cpp.

pcl::PointIndices::Ptr jsk_footstep_planner::FootstepState::cropPointCloudExact ( pcl::PointCloud< pcl::PointNormal >::Ptr  cloud,
pcl::PointIndices::Ptr  near_indices,
double  padding_x = 0.0,
double  padding_y = 0.0 
)

Definition at line 112 of file footstep_state.cpp.

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

Definition at line 118 of file footstep_state.h.

bool jsk_footstep_planner::FootstepState::crossCheck ( FootstepState::Ptr  other,
float  collision_padding = 0 
) [virtual]

return true if this and other are collision free.

Definition at line 183 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 592 of file footstep_state.cpp.

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

Definition at line 207 of file footstep_state.h.

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

Definition at line 206 of file footstep_state.h.

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

Definition at line 200 of file footstep_state.h.

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

Definition at line 215 of file footstep_state.h.

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

Definition at line 220 of file footstep_state.h.

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

Definition at line 218 of file footstep_state.h.

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

Definition at line 219 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 467 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 539 of file footstep_state.cpp.

Eigen::Affine3f jsk_footstep_planner::FootstepState::midcoords ( const FootstepState other) [virtual]

Definition at line 605 of file footstep_state.cpp.

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

Definition at line 208 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,
FootstepParameters parameters 
) [virtual]

Definition at line 210 of file footstep_state.cpp.

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

Definition at line 201 of file footstep_state.h.

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

Definition at line 171 of file footstep_state.h.

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

Definition at line 85 of file footstep_state.cpp.

jsk_footstep_msgs::Footstep::Ptr jsk_footstep_planner::FootstepState::toROSMsg ( const Eigen::Vector3f &  ioffset) [virtual]

Definition at line 96 of file footstep_state.cpp.

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

Definition at line 178 of file footstep_state.h.


Member Data Documentation

Definition at line 249 of file footstep_state.h.

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

Definition at line 243 of file footstep_state.h.

Definition at line 246 of file footstep_state.h.

Definition at line 247 of file footstep_state.h.

Definition at line 248 of file footstep_state.h.

Definition at line 245 of file footstep_state.h.

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

Definition at line 242 of file footstep_state.h.

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

Definition at line 244 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 Fri Apr 19 2019 03:45:28