footstep_projection_demo.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 #include <jsk_footstep_msgs/FootstepArray.h>
00036 #include "jsk_footstep_planner/footstep_state.h"
00037 #include <interactive_markers/tools.h>
00038 #include <interactive_markers/interactive_marker_server.h>
00039 #include <jsk_recognition_utils/pcl_conversion_util.h>
00040 
00041 //#include <jsk_interactive_marker/interactive_marker_helpers.h>
00042 using namespace jsk_footstep_planner;
00043 
00044 // globals
00045 ros::Publisher pub_footstep;
00046 ros::Publisher pub_projected_footstep;
00047 ros::Publisher pub_cloud;
00048 FootstepState::Ptr original_footstep;
00049 pcl::PointCloud<pcl::PointNormal>::Ptr cloud;
00050 pcl::KdTreeFLANN<pcl::PointNormal> tree;
00051 pcl::PointCloud<pcl::PointNormal>::Ptr cloud2d;
00052 pcl::search::Octree<pcl::PointNormal> tree2d(0.1);
00053 ANNGrid::Ptr grid_search;
00054 
00055 jsk_footstep_msgs::FootstepArray footstepToFootstepArray(
00056   jsk_footstep_msgs::Footstep msg)
00057 {
00058   jsk_footstep_msgs::FootstepArray array_msg;
00059   array_msg.header.frame_id = "odom";
00060   array_msg.header.stamp = ros::Time::now();
00061   array_msg.footsteps.push_back(msg);
00062   return array_msg;
00063 }
00064 
00065 void processFeedback(
00066     const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
00067 {
00068   Eigen::Affine3f new_pose;
00069   tf::poseMsgToEigen(feedback->pose, new_pose);
00070   original_footstep->setPose(new_pose);
00071   jsk_footstep_msgs::FootstepArray msg = footstepToFootstepArray(*(original_footstep->toROSMsg()));
00072   pub_footstep.publish(msg);
00073   unsigned int error_state;
00074   FootstepState::Ptr projected_footstep = original_footstep->projectToCloud(
00075     tree,
00076     cloud,
00077     grid_search,
00078     tree2d,
00079     cloud2d,
00080     Eigen::Vector3f(0, 0, 1),
00081     error_state,
00082     0.05,
00083     100,
00084     10);
00085   if (projected_footstep) {
00086     jsk_footstep_msgs::FootstepArray msg2 = footstepToFootstepArray(*(projected_footstep->toROSMsg()));
00087     pub_projected_footstep.publish(msg2);
00088   }
00089   else {
00090     ROS_ERROR("error state: %u" , error_state);
00091   }
00092 }
00093 
00094 pcl::PointCloud<pcl::PointNormal>::Ptr
00095 generateCloud()
00096 {
00097   pcl::PointCloud<pcl::PointNormal>::Ptr gen_cloud(new pcl::PointCloud<pcl::PointNormal>);
00098   for (double y = -0.5; y < 0.5; y = y + 0.01) {
00099     for (double x = 0.0; x < 0.5; x = x + 0.01) {
00100       pcl::PointNormal p;
00101       p.x = x;
00102       p.y = y;
00103       gen_cloud->points.push_back(p);
00104     }
00105     for (double x = 0.5; x < 1.0; x = x + 0.01) {
00106       pcl::PointNormal p;
00107       p.x = x;
00108       p.y = y;
00109       p.z = x - 0.5;
00110       gen_cloud->points.push_back(p);
00111     }
00112     for (double x = 1.0; x < 1.5; x = x + 0.01) {
00113       pcl::PointNormal p;
00114       p.x = x;
00115       p.y = y;
00116       p.z = 0.5;
00117       gen_cloud->points.push_back(p);
00118     }
00119     for (double x = 1.5; x < 2.0; x = x + 0.01) {
00120       pcl::PointNormal p;
00121       p.x = x;
00122       p.y = y;
00123       p.z = -x + 2.0;
00124       gen_cloud->points.push_back(p);
00125     }
00126     for (double x = 2.0; x < M_PI; x = x + 0.01) {
00127       pcl::PointNormal p;
00128       p.x = x;
00129       p.y = y;
00130       gen_cloud->points.push_back(p);
00131     }
00132     for (double x = M_PI; x < 2.0 * M_PI; x = x + 0.01) {
00133       pcl::PointNormal p;
00134       p.x = x;
00135       p.y = y;
00136       p.z = std::abs(sin(2.0 * x));
00137       gen_cloud->points.push_back(p);
00138     }
00139 
00140   }
00141   return gen_cloud;
00142 }
00143 
00144 int main(int argc, char** argv)
00145 {
00146   ros::init(argc, argv, "footstep_projection_demo");
00147   ros::NodeHandle nh("~");
00148   pub_footstep
00149     = nh.advertise<jsk_footstep_msgs::FootstepArray>("original", 1);
00150   pub_projected_footstep
00151     = nh.advertise<jsk_footstep_msgs::FootstepArray>("projected", 1);
00152   pub_cloud
00153     = nh.advertise<sensor_msgs::PointCloud2>("cloud", 1, true);
00154   
00155   // generate pointcloud
00156   cloud = generateCloud();
00157   cloud2d.reset(new pcl::PointCloud<pcl::PointNormal>);
00158   tree.setInputCloud(cloud);
00159   grid_search.reset(new ANNGrid(0.1));
00160   grid_search->build(*cloud);
00161   pcl::ProjectInliers<pcl::PointNormal> proj;
00162   pcl::ModelCoefficients::Ptr coef (new pcl::ModelCoefficients);
00163   
00164   coef->values.resize(4);
00165   coef->values[2] = 1.0;
00166   proj.setInputCloud(cloud);
00167   proj.setModelCoefficients(coef);
00168   proj.filter(*cloud2d);
00169   tree2d.setInputCloud(cloud2d);
00170   sensor_msgs::PointCloud2 ros_cloud;
00171   pcl::toROSMsg(*cloud, ros_cloud);
00172   ros_cloud.header.frame_id = "odom";
00173   ros_cloud.header.stamp = ros::Time::now();
00174   pub_cloud.publish(ros_cloud);
00175   original_footstep.reset(new FootstepState(jsk_footstep_msgs::Footstep::LEFT,
00176                                             Eigen::Affine3f::Identity(),
00177                                             Eigen::Vector3f(0.2, 0.1, 0.00001),
00178                                             Eigen::Vector3f(0.05, 0.05, 0.8)));
00179   jsk_footstep_msgs::FootstepArray msg = footstepToFootstepArray(*(original_footstep->toROSMsg()));
00180   pub_footstep.publish(msg);
00181   interactive_markers::InteractiveMarkerServer server("footstep_projection_demo");
00182   visualization_msgs::InteractiveMarker int_marker;
00183   int_marker.header.frame_id = "/odom";
00184   int_marker.header.stamp=ros::Time::now();
00185   int_marker.name = "footstep marker";
00186 
00187   visualization_msgs::InteractiveMarkerControl control;
00188 
00189   control.orientation.w = 1;
00190   control.orientation.x = 1;
00191   control.orientation.y = 0;
00192   control.orientation.z = 0;
00193   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00194   int_marker.controls.push_back(control);
00195   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00196   int_marker.controls.push_back(control);
00197 
00198   control.orientation.w = 1;
00199   control.orientation.x = 0;
00200   control.orientation.y = 1;
00201   control.orientation.z = 0;
00202   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00203   int_marker.controls.push_back(control);
00204   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00205   int_marker.controls.push_back(control);
00206 
00207   control.orientation.w = 1;
00208   control.orientation.x = 0;
00209   control.orientation.y = 0;
00210   control.orientation.z = 1;
00211   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00212   int_marker.controls.push_back(control);
00213   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00214   int_marker.controls.push_back(control);
00215   
00216   server.insert(int_marker, &processFeedback);
00217   server.applyChanges();
00218   ros::spin();
00219 }


jsk_footstep_planner
Author(s): Ryohei Ueda
autogenerated on Wed Sep 16 2015 04:37:56