37 #ifndef JSK_FOOTSTEP_PLANNER_FOOTSTEP_STATE_H_
38 #define JSK_FOOTSTEP_PLANNER_FOOTSTEP_STATE_H_
40 #include <jsk_footstep_msgs/Footstep.h>
42 #include <pcl/kdtree/kdtree_flann.h>
43 #include <pcl/filters/crop_box.h>
44 #include <pcl/sample_consensus/method_types.h>
45 #include <pcl/sample_consensus/model_types.h>
46 #include <pcl/segmentation/sac_segmentation.h>
47 #include <pcl/segmentation/sac_segmentation.h>
48 #include <pcl/filters/project_inliers.h>
49 #include <pcl/search/octree.h>
58 namespace projection_state
85 const Eigen::Affine3f& pose,
86 const Eigen::Vector3f& dimensions,
91 float x =
pose_.translation()[0];
92 float y =
pose_.translation()[1];
93 float roll, pitch, yaw;
94 pcl::getEulerAngles(
pose_, roll, pitch, yaw);
101 const Eigen::Affine3f& pose,
102 const Eigen::Vector3f& dimensions,
115 const Eigen::Vector3f& size,
118 inline float cross2d(
const Eigen::Vector2f& a,
const Eigen::Vector2f& b)
const
120 return a[0] *
b[1] -
a[1] *
b[0];
122 virtual jsk_footstep_msgs::Footstep::Ptr
toROSMsg();
123 virtual jsk_footstep_msgs::Footstep::Ptr
toROSMsg(
const Eigen::Vector3f& ioffset);
127 pcl::PointCloud<pcl::PointNormal>::Ptr
cloud,
129 pcl::search::Octree<pcl::PointNormal>& tree_2d,
130 pcl::PointCloud<pcl::PointNormal>::Ptr cloud_2d,
131 const Eigen::Vector3f& z,
132 unsigned int& error_state,
133 double outlier_threshold,
136 int foot_x_sampling_num = 3,
137 int foot_y_sampling_num = 3,
138 double vertex_threshold = 0.02,
139 const bool skip_cropping =
true,
140 const bool use_normal =
false,
141 double normal_distance_weight = 0.2,
142 double normal_opening_angle = 0.2,
143 double min_ratio_of_inliers = 0.8);
147 pcl::PointCloud<pcl::PointNormal>::Ptr
cloud,
149 pcl::search::Octree<pcl::PointNormal>& tree_2d,
150 pcl::PointCloud<pcl::PointNormal>::Ptr cloud_2d,
151 const Eigen::Vector3f& z,
152 unsigned int& error_state,
156 pcl::PointIndices::Ptr
158 pcl::search::Octree<pcl::PointNormal>&
tree);
160 pcl::PointIndices::Ptr
163 double padding_x = 0.0,
double padding_y = 0.0);
165 pcl::PointIndices::Ptr
167 pcl::PointIndices::Ptr near_indices,
168 double padding_x = 0.0,
double padding_y = 0.0);
170 template <
class Po
intT>
174 p.getVector3fMap() = Eigen::Vector3f(
pose_.translation());
178 inline void vertices(Eigen::Vector3f& a,
182 double collision_padding = 0)
184 const Eigen::Vector3f ux = Eigen::Vector3f::UnitX();
185 const Eigen::Vector3f uy = Eigen::Vector3f::UnitY();
188 a = Eigen::Vector3f((
pose_ * Eigen::Translation3f( ux * dim0 / 2 + uy * dim1 / 2)).translation());
189 b = Eigen::Vector3f((
pose_ * Eigen::Translation3f(- ux * dim0 / 2 + uy * dim1 / 2)).translation());
190 c = Eigen::Vector3f((
pose_ * Eigen::Translation3f(- ux * dim0 / 2 - uy * dim1 / 2)).translation());
191 d = Eigen::Vector3f((
pose_ * Eigen::Translation3f( ux * dim0 / 2 - uy * dim1 / 2)).translation());
200 virtual Eigen::Affine3f
getPose()
const {
return pose_; }
201 virtual void setPose(
const Eigen::Affine3f& pose)
225 pcl::PointCloud<pcl::PointNormal>::Ptr
cloud,
226 pcl::KdTreeFLANN<pcl::PointNormal>&
tree,
227 pcl::PointIndices::Ptr inliers,
228 const int foot_x_sampling_num,
229 const int foot_y_sampling_num,
230 const double vertex_threshold);
233 pcl::PointCloud<pcl::PointNormal>::Ptr
cloud,
234 pcl::KdTreeFLANN<pcl::PointNormal>&
tree,
235 pcl::PointIndices::Ptr inliers,
236 const int foot_x_sampling_num,
237 const int foot_y_sampling_num,
238 const double vertex_threshold);
242 Eigen::Affine3f
pose_;
256 return std::abs(
s->indexX()) << (25 + 14) + std::abs(
s->indexY()) << 14
257 + std::abs(
s->indexT());