pose_sampling_helpers.h
Go to the documentation of this file.
1 //
2 // Created by yijiangh on 4/9/18.
3 //
4 
5 #ifndef FRAMEFAB_MPP_POSE_SAMPLING_HELPERS_H
6 #define FRAMEFAB_MPP_POSE_SAMPLING_HELPERS_H
7 
9 
10 #include <Eigen/Core>
11 #include <Eigen/Geometry>
12 
13 namespace descartes_planner
14 {
15 
16 std::vector<Eigen::Vector3d> discretizePositions(
17  const Eigen::Vector3d& start, const Eigen::Vector3d& stop, const double ds);
18 
19 Eigen::Affine3d makePose(const Eigen::Vector3d& position, const Eigen::Matrix3d& orientation,
20  const double z_axis_angle);
21 
22 Eigen::Affine3d makePose(const Eigen::Vector3d& position, const Eigen::Matrix3d& orientation);
23 
24 int randomSampleInt(int lower, int upper);
25 
26 double randomSampleDouble(double lower, double upper);
27 
28 std::vector<Eigen::Affine3d> generateSample(const descartes_planner::CapRung& cap_rung,
29  descartes_planner::CapVert& cap_vert);
30 
31 
32 std::vector<std::vector<Eigen::Affine3d>> generateSamplePickNPlace(const descartes_planner::CapRung& cap_rung,
33  descartes_planner::CapVert& cap_vert);
34 
35 }
36 
37 #endif //FRAMEFAB_MPP_POSE_SAMPLING_HELPERS_H
std::vector< Eigen::Vector3d > discretizePositions(const Eigen::Vector3d &start, const Eigen::Vector3d &stop, const double ds)
std::vector< std::vector< Eigen::Affine3d > > generateSamplePickNPlace(const descartes_planner::CapRung &cap_rung, descartes_planner::CapVert &cap_vert)
int randomSampleInt(int lower, int upper)
Eigen::Affine3d makePose(const Eigen::Vector3d &position, const Eigen::Matrix3d &orientation, const double z_axis_angle)
std::vector< Eigen::Affine3d > generateSample(const descartes_planner::CapRung &cap_rung, descartes_planner::CapVert &cap_vert)
double randomSampleDouble(double lower, double upper)


choreo_descartes_planner
Author(s): Yijiang Huang , Jonathan Meyer
autogenerated on Thu Jul 18 2019 03:58:35