35 #include <jsk_footstep_msgs/FootstepArray.h> 
   40 #include <boost/random.hpp> 
   42 #include <boost/program_options.hpp> 
   43 #include <boost/algorithm/string.hpp> 
   50 #define OPTION_DEFAULT_VALUE(TYPE, VALUE) boost::program_options::value<TYPE>()->default_value(VALUE) 
   51 #define OPTION_TYPE(TYPE) boost::program_options::value<TYPE>() 
   55   std::vector<Eigen::Affine3f> successors;
 
   74                                              Eigen::Affine3f::Identity(),
 
   78   graph->setBasicSuccessors(successors);
 
   81 inline bool planBench(
double x, 
double y, 
double yaw,
 
   84                       const std::string heuristic,
 
   85                       const double first_rotation_weight,
 
   86                       const double second_rotation_weight,
 
   91                                                  goal_center * Eigen::Translation3f(0, 0.1, 0),
 
   95                                                   goal_center * Eigen::Translation3f(0, -0.1, 0),
 
   98   graph->setGoalState(left_goal, right_goal);
 
  100   if (
graph->usePointCloudModel()) {
 
  101     if (!
graph->projectGoal()) {
 
  108   if (heuristic == 
"step_cost") {
 
  111   else if (heuristic == 
"zero") {
 
  114   else if (heuristic == 
"straight") {
 
  117   else if (heuristic == 
"straight_rotation") {
 
  131     printf(
"%d/%d (%d%) [", 
x, 
n, (
int)(
ratio*100) );
 
  134     for (
int x=0; 
x<
c; 
x++)
 
  137     for (
int x=
c; 
x<
w; 
x++)
 
  142     printf(
"]\n\033[F\033[J");
 
  146 int main(
int argc, 
char** argv)
 
  150   boost::program_options::options_description opt(
"Options");
 
  163      "heuristic function (zero, straight, straight_rotation, step_cost)")
 
  165      "first rotation weight of step_cost heuristic")
 
  167      "second rotation weight of step_cost heuristic")
 
  169      "pointcloud model (none, flat, stairs, hilld, gaussian)")
 
  170     (
"enable_lazy_perception", 
"Enable Lazy Perception")
 
  171     (
"enable_local_movement", 
"Enable Local Movement")
 
  174     (
"verbose,v", 
"verbose")
 
  175     (
"help,h", 
"Show help");
 
  177   boost::program_options::variables_map vm;
 
  178   boost::program_options::store(boost::program_options::parse_command_line(argc, 
argv, opt), vm);
 
  179   boost::program_options::notify(vm);
 
  181   if (vm.count(
"help")) {
 
  182     std::cout << opt << std::endl;
 
  186   const double min_x = vm[
"min_x"].as<
double>();
 
  187   const double max_x = vm[
"max_x"].as<
double>();
 
  188   const double dx = vm[
"dx"].as<
double>();
 
  189   const double min_y = vm[
"min_y"].as<
double>();
 
  190   const double max_y = vm[
"max_y"].as<
double>();
 
  191   const double dy = vm[
"dy"].as<
double>();
 
  192   const double resolution_x = vm[
"resolution_x"].as<
double>();
 
  193   const double resolution_y = vm[
"resolution_y"].as<
double>();
 
  194   const double resolution_theta = vm[
"resolution_theta"].as<
double>();
 
  195   const int n_theta = vm[
"n_theta"].as<
int>();
 
  196   const std::string heuristic = vm[
"heuristic"].as<std::string>();
 
  197   const double first_rotation_weight = vm[
"first_rotation_weight"].as<
double>();
 
  198   const double second_rotation_weight = vm[
"second_rotation_weight"].as<
double>();
 
  199   const std::string 
model = vm[
"model"].as<std::string>();
 
  200   const bool enable_perception = vm[
"model"].as<std::string>() != 
"none";
 
  201   const bool enable_lazy_perception = vm.count(
"enable_lazy_perception") > 0;
 
  202   const bool enable_local_movement = vm.count(
"enable_local_movement") > 0;
 
  203   const bool verbose = vm.count(
"verbose") > 0;
 
  204   const int test_count = vm[
"test_count"].as<
int>();
 
  205   const std::string output_filename = vm[
"output"].as<std::string>();
 
  208   std::cout << 
"parameters" << std::endl;
 
  209   std::cout << 
"  min_x: " << min_x << std::endl;
 
  210   std::cout << 
"  max_x: " << max_x << std::endl;
 
  211   std::cout << 
"  dx: " << 
dx << std::endl;
 
  212   std::cout << 
"  min_y: " << min_y << std::endl;
 
  213   std::cout << 
"  max_y: " << max_y << std::endl;
 
  214   std::cout << 
"  dy: " << 
dy << std::endl;
 
  215   std::cout << 
"  resolution_x: " << resolution_x << std::endl;
 
  216   std::cout << 
"  resolution_y: " << resolution_y << std::endl;
 
  217   std::cout << 
"  resolution_theta: " << resolution_theta << std::endl;
 
  218   std::cout << 
"  n_theta: " << n_theta << std::endl;
 
  219   std::cout << 
"  heuristic: " << heuristic << std::endl;
 
  220   std::cout << 
"  first_rotation_weight: " << first_rotation_weight << std::endl;
 
  221   std::cout << 
"  second_rotation_weight: " << second_rotation_weight << std::endl;
 
  222   std::cout << 
"  model: " << 
model << std::endl;
 
  223   std::cout << 
"  enable_lazy_perception: " << enable_lazy_perception << std::endl;
 
  224   std::cout << 
"  enable_local_movement: " << enable_local_movement << std::endl;
 
  225   std::cout << 
"  test_count: " << test_count << std::endl;
 
  226   std::cout << 
"  output: " << output_filename << std::endl;
 
  227   std::cout << 
"  verbose: " << 
verbose << std::endl;
 
  230   pcl::PointCloud<pcl::PointNormal>::Ptr 
cloud (
new pcl::PointCloud<pcl::PointNormal>);
 
  231   if (
model != 
"none") {
 
  234   Eigen::Vector3f 
res(resolution_x, resolution_y, resolution_theta);
 
  236   if (enable_perception) {
 
  241   if (enable_perception) {
 
  242     if (!
graph->projectStart()) {
 
  243       ROS_FATAL(
"Failed to project start state");
 
  247   std::cout << 
graph->infoString() << std::endl;
 
  248   std::ofstream 
ofs(output_filename.c_str());
 
  249   int test_num = n_theta * ceil((max_x - min_x) / 
dx + 1) * ceil((max_y - min_y) / 
dy + 1);
 
  252   ofs << 
"x,y,theta,one_time," 
  253       << 
"min_x,max_x,dx,min_y,max_y,dy," 
  254       << 
"resolution_x,resolution_y,resolution_theta,n_theta," 
  255       << 
"heuristic,first_rotation_weight,second_rotation_weight," 
  257       << 
"enable_lazy_perception,enable_local_movement," 
  258       << 
"test_count" << std::endl;
 
  260   for (
size_t ti = 0; ti < n_theta; ti++) {
 
  261     double theta = 2.0 * 
M_PI / n_theta * ti ;
 
  262     for (
double x = min_x; 
x <= max_x; 
x += 
dx) {
 
  263       for (
double y = min_y; 
y <= max_y; 
y += 
dy) {
 
  269         for (
size_t i = 0; 
i < test_count; 
i++) {
 
  277           std::cout << 
"Planning took " << (
end-
start).toSec()/test_count << 
" sec" << std::endl;
 
  280           double time_to_solve = (
end - 
start).toSec() / test_count;
 
  281           ofs << 
x << 
"," << 
y << 
"," << 
theta << 
"," << time_to_solve
 
  282               << 
"," << min_x << 
"," << max_x << 
"," << 
dx << 
"," << min_y << 
"," << max_y << 
"," << 
dy 
  283               << 
"," << resolution_x << 
"," << resolution_y << 
"," << resolution_theta << 
"," << n_theta
 
  284               << 
"," << heuristic << 
"," << first_rotation_weight << 
"," << second_rotation_weight
 
  286               << 
"," << enable_lazy_perception << 
"," << enable_local_movement
 
  287               << 
"," << test_count << std::endl;
 
  297   std::cout << 
"Plot result by scripts/plot_bench.py" << std::endl;