35 #include <jsk_footstep_msgs/FootstepArray.h>
40 #include <boost/random.hpp>
44 const Eigen::Vector3f
resolution(0.05, 0.05, 0.08);
46 void plan(
double x,
double y,
double yaw,
53 goal_center * Eigen::Translation3f(0, 0.1, 0),
57 goal_center * Eigen::Translation3f(0, -0.1, 0),
61 jsk_footstep_msgs::FootstepArray ros_goal;
62 ros_goal.header.frame_id =
"odom";
64 ros_goal.footsteps.push_back(*left_goal->toROSMsg());
65 ros_goal.footsteps.push_back(*right_goal->toROSMsg());
68 graph->setGoalState(left_goal, right_goal);
75 std::vector<SolverNode<FootstepState, FootstepGraph>::Ptr> path = solver.
solve();
77 std::cout <<
"took " << (end_time -
start_time).toSec() <<
" sec" << std::endl;
78 std::cout <<
"path: " << path.size() << std::endl;
79 jsk_footstep_msgs::FootstepArray ros_path;
80 ros_path.header.frame_id =
"odom";
82 for (
size_t i = 0;
i < path.size();
i++) {
83 ros_path.footsteps.push_back(*path[
i]->getState()->
toROSMsg());
88 int main(
int argc,
char** argv)
95 boost::mt19937 rng(
static_cast<unsigned long>(time(0)) );
96 boost::uniform_real<> xyrange(-3.0,3.0);
97 boost::variate_generator< boost::mt19937, boost::uniform_real<> > pos_rand(rng, xyrange);
98 boost::uniform_real<> trange(0, 2 *
M_PI);
99 boost::variate_generator< boost::mt19937, boost::uniform_real<> > rot_rand(rng, trange);
104 std::vector<Eigen::Affine3f> successors;
123 Eigen::Affine3f::Identity(),
127 graph->setBasicSuccessors(successors);
128 jsk_footstep_msgs::FootstepArray ros_start;
129 ros_start.header.frame_id =
"odom";
131 ros_start.footsteps.push_back(*
start->toROSMsg());