6 #include <jsk_topic_tools/rosparam_utils.h> 
   10 #include <visualization_msgs/MarkerArray.h> 
   18     plane_tree_(new 
pcl::KdTreeFLANN<
pcl::PointNormal>),
 
   19     obstacle_tree_(new 
pcl::KdTreeFLANN<
pcl::PointXYZ>)
 
   32     std::vector<double> collision_bbox_size, collision_bbox_offset;
 
   33     if (jsk_topic_tools::readVectorParameter(nh, 
"collision_bbox_size", collision_bbox_size)) {
 
   38     if (jsk_topic_tools::readVectorParameter(nh, 
"collision_bbox_offset", collision_bbox_offset)) {
 
   40                                                                                   collision_bbox_offset[1],
 
   41                                                                                   collision_bbox_offset[2]);
 
   59     Eigen::Vector4f minpt, maxpt;
 
   60     pcl::getMinMax3D<pcl::PointNormal> (*
plane_points_, minpt, maxpt);
 
   62     Eigen::Vector4f len = maxpt - minpt;
 
   69     ROS_INFO(
"min_point: [%f, %f] / size: %d %d",
 
   84     ROS_INFO(
"obstacle points is updated");
 
   94     ROS_INFO(
"pointcloud points is updated");
 
  101       jsk_footstep_planner::CollisionBoundingBoxInfo::Request& req,
 
  102       jsk_footstep_planner::CollisionBoundingBoxInfo::Response& res)
 
  113                                     const std::string& text,
 
  116     std_msgs::ColorRGBA ok_color;
 
  117     ok_color.r = 0.3568627450980392;
 
  118     ok_color.g = 0.7529411764705882;
 
  119     ok_color.b = 0.8705882352941177;
 
  121     std_msgs::ColorRGBA warn_color;
 
  122     warn_color.r = 0.9411764705882353;
 
  123     warn_color.g = 0.6784313725490196;
 
  124     warn_color.b = 0.3058823529411765;
 
  126     std_msgs::ColorRGBA error_color;
 
  127     error_color.r = 0.8509803921568627;
 
  128     error_color.g = 0.3254901960784314;
 
  129     error_color.b = 0.30980392156862746;
 
  131     std_msgs::ColorRGBA color;
 
  141     jsk_rviz_plugins::OverlayText 
msg;
 
  147     msg.bg_color.a = 0.0;
 
  148     msg.fg_color = color;
 
  160     std::string goal_frame_id = goal->initial_footstep.header.frame_id;
 
  165         ROS_ERROR(
"frame_id of goal and pointcloud do not match. goal: %s, pointcloud: %s.",
 
  174         ROS_ERROR(
"frame_id of goal and obstacle pointcloud do not match. goal: %s, obstacle: %s.",
 
  185     for(
int i = 0; 
i < goal->initial_footstep.footsteps.size(); 
i++) {
 
  186       initx += goal->initial_footstep.footsteps[
i].pose.position.x;
 
  187       inity += goal->initial_footstep.footsteps[
i].pose.position.y;
 
  189     initx /= goal->initial_footstep.footsteps.size();
 
  190     inity /= goal->initial_footstep.footsteps.size();
 
  191     for(
int i = 0; 
i < goal->goal_footstep.footsteps.size(); 
i++) {
 
  192       goalx += goal->goal_footstep.footsteps[
i].pose.position.x;
 
  193       goaly += goal->goal_footstep.footsteps[
i].pose.position.y;
 
  195     goalx /= goal->initial_footstep.footsteps.size();
 
  196     goaly /= goal->initial_footstep.footsteps.size();
 
  198     ROS_INFO(
"start: %f %f, goal %f %f", initx, inity, goalx, goaly);
 
  204     Eigen::Vector3f startp(initx, inity, 0);
 
  205     Eigen::Vector3f goalp(goalx, goaly, 0);
 
  211       ROS_ERROR(
"start is not in range %d %d", sx, sy);
 
  217       ROS_ERROR(
"goal is not in range %d %d", gx, gy);
 
  225     if(start_state->getOccupancy() != 0) {
 
  230     if(goal_state->getOccupancy() != 0) {
 
  236     graph_->setStartState(start_state);
 
  237     graph_->setGoalState(goal_state);
 
  244     if(path.size() < 1) {
 
  251     ROS_INFO(
"solved path_size: %d", path.size());
 
  252     std::vector<Eigen::Vector3f > 
points;
 
  253     for(
int i = 0; 
i < path.size(); 
i++) {
 
  255       int ix = path[
i]->getState()->indexX();
 
  256       int iy = path[
i]->getState()->indexY();
 
  260       ROS_INFO(
"path %d (%f %f) [%d - %d]", 
i, ix, iy, 
p[0], 
p[1]);
 
  264       visualization_msgs::MarkerArray ma;
 
  265       visualization_msgs::Marker m;
 
  267       m.header.frame_id = 
"map";
 
  270       ma.markers.push_back(m);
 
  277       jsk_footstep_msgs::PlanFootstepsResult 
result_;
 
  278       result_.result.header = goal->goal_footstep.header;
 
  280       std::vector<Eigen::Vector3f > 
points;
 
  281       for(
int i = 0; 
i < path.size(); 
i++) {
 
  282         int ix = path[
i]->getState()->indexX();
 
  283         int iy = path[
i]->getState()->indexY();
 
  286         jsk_footstep_msgs::Footstep fs;
 
  287         fs.leg = jsk_footstep_msgs::Footstep::LLEG;
 
  290         fs.dimensions.z = 0.01;
 
  291         fs.pose.orientation.x = 0;
 
  292         fs.pose.orientation.y = 0;
 
  293         fs.pose.orientation.z = 0;
 
  294         fs.pose.orientation.w = 1;
 
  295         fs.pose.position.x = 
p[0];
 
  296         fs.pose.position.y = 
p[1];
 
  297         fs.pose.position.z = 
p[2];
 
  298         result_.result.footsteps.push_back(fs);
 
  304     pcl::PointCloud<pcl::PointXYZRGB> close_list_cloud, open_list_cloud;
 
  313                 (boost::format(
"Took %f sec\nPerception took %f sec\nPlanning took %f sec\n%lu path\nopen list: %lu\nclose list:%lu")
 
  315                  % 
graph_->getPerceptionDuration().toSec()
 
  316                  % (planning_duration - 
graph_->getPerceptionDuration().toSec())
 
  318                  % open_list_cloud.points.size()
 
  319                  % close_list_cloud.points.size()).str(),
 
  326     const pcl::PointCloud<pcl::PointXYZRGB>& 
cloud,
 
  328     const std_msgs::Header& header)
 
  330     sensor_msgs::PointCloud2 ros_cloud;
 
  332     ros_cloud.header = 
header;
 
  333     pub.publish(ros_cloud);
 
  347       std::vector<double> 
pos;
 
  350       for(std::vector<double>::iterator it = 
pos.begin();
 
  351           it != 
pos.end(); it++) {
 
  352         std::vector<int> near_indices;
 
  353         std::vector<float> distances;
 
  354         pcl::PointXYZ center;
 
  356         center.getVector3fMap() = 
p;
 
  361         size += near_indices.size();
 
  364         ptr->setOccupancy(1);
 
  366         ptr->setOccupancy(0);
 
  376       std::vector<int> plane_indices;
 
  377       std::vector<float> distances;
 
  378       pcl::PointNormal center;
 
  379       center.getVector3fMap() = 
p;
 
  384       if (plane_indices.size() < 50) { 
 
  385         ptr->setOccupancy(2 + ptr->getOccupancy());
 
  395     visualization_msgs::MarkerArray ma;
 
  401       visualization_msgs::Marker m;
 
  402       m.header.frame_id = 
"map";
 
  403       m.type = visualization_msgs::Marker::CUBE_LIST;
 
  413       for(
int y = 0; 
y < sy; 
y++) {
 
  414         for(
int x = 0; 
x < sx; 
x++) {
 
  419           geometry_msgs::Point gp;
 
  423           m.points.push_back(gp);
 
  425           std_msgs::ColorRGBA col;
 
  426           if(st->getOccupancy() == 1) {
 
  431           } 
else if(st->getOccupancy() == 2) {
 
  436           } 
else if(st->getOccupancy() == 3) {
 
  448           m.colors.push_back(col);
 
  451       ma.markers.push_back(m);