footstep_planning_2d_interactive_demo.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 #include <jsk_footstep_msgs/FootstepArray.h>
39 #include <time.h>
40 #include <boost/random.hpp>
44 #include <jsk_rviz_plugins/OverlayText.h>
45 #include <boost/format.hpp>
46 using namespace jsk_footstep_planner;
47 
48 const Eigen::Vector3f footstep_size(0.2, 0.1, 0.000001);
49 const Eigen::Vector3f resolution(0.05, 0.05, 0.08);
52 
54 {
55  ROS_INFO("open list: %lu", solver.getOpenList().size());
56  ROS_INFO("close list: %lu", solver.getCloseList().size());
57 }
58 
59 void plan(const Eigen::Affine3f& goal_center,
60  FootstepGraph::Ptr graph, ros::Publisher& pub_path,
61  ros::Publisher& pub_goal,
62  Eigen::Vector3f footstep_size)
63 {
64  FootstepState::Ptr left_goal(new FootstepState(jsk_footstep_msgs::Footstep::LEFT,
65  goal_center * Eigen::Translation3f(0, 0.1, 0),
66  footstep_size,
67  resolution));
68  FootstepState::Ptr right_goal(new FootstepState(jsk_footstep_msgs::Footstep::RIGHT,
69  goal_center * Eigen::Translation3f(0, -0.1, 0),
70  footstep_size,
71  resolution));
72 
73  jsk_footstep_msgs::FootstepArray ros_goal;
74  ros_goal.header.frame_id = "odom";
75  ros_goal.header.stamp = ros::Time::now();
76  ros_goal.footsteps.push_back(*left_goal->toROSMsg());
77  ros_goal.footsteps.push_back(*right_goal->toROSMsg());
78  pub_goal.publish(ros_goal);
79 
80  graph->setGoalState(left_goal, right_goal);
81  //AStarSolver<FootstepGraph> solver(graph);
82  FootstepAStarSolver<FootstepGraph> solver(graph, 100, 100, 100);
83  //solver.setHeuristic(&footstepHeuristicStraight);
84  //solver.setHeuristic(&footstepHeuristicStraightRotation);
85  solver.setHeuristic(boost::bind(&footstepHeuristicStepCost, _1, _2, 1.0, 0.1));
86  solver.setProfileFunction(&profile);
87  ros::WallTime start_time = ros::WallTime::now();
88  std::vector<SolverNode<FootstepState, FootstepGraph>::Ptr> path = solver.solve();
89  ros::WallTime end_time = ros::WallTime::now();
90  std::cout << "took " << (end_time - start_time).toSec() << " sec" << std::endl;
91  std::cout << "path: " << path.size() << std::endl;
92  jsk_footstep_msgs::FootstepArray ros_path;
93  ros_path.header.frame_id = "odom";
94  ros_path.header.stamp = ros::Time::now();
95  for (size_t i = 0; i < path.size(); i++) {
96  ros_path.footsteps.push_back(*path[i]->getState()->toROSMsg());
97  }
98  pub_path.publish(ros_path);
99 
100 }
101 
102 
104  const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
105 {
106  Eigen::Affine3f new_pose;
107  tf::poseMsgToEigen(feedback->pose, new_pose);
109  plan(new_pose, graph, pub_path, pub_goal, footstep_size);
111  jsk_rviz_plugins::OverlayText text;
112  text.bg_color.a = 0.0;
113  text.fg_color.a = 1.0;
114  text.fg_color.r = 25 / 255.0;
115  text.fg_color.g = 1.0;
116  text.fg_color.b = 250 / 255.0;
117  text.line_width = 2;
118  text.top = 10;
119  text.left = 10;
120  text.text_size = 24;
121  text.width = 600;
122  text.height = 100;
123  text.text = (boost::format("Planning took %f sec") % (end - start).toSec()).str();
124  pub_text.publish(text);
125 }
126 
127 int main(int argc, char** argv)
128 {
129  ros::init(argc, argv, "foootstep_planning_2d");
130  ros::NodeHandle nh("~");
131  ros::Publisher pub_start = nh.advertise<jsk_footstep_msgs::FootstepArray>("start", 1, true);
132  pub_goal = nh.advertise<jsk_footstep_msgs::FootstepArray>("goal", 1, true);
133  pub_path = nh.advertise<jsk_footstep_msgs::FootstepArray>("path", 1, true);
134  pub_text = nh.advertise<jsk_rviz_plugins::OverlayText>("text", 1, true);
135  boost::mt19937 rng( static_cast<unsigned long>(time(0)) );
136  boost::uniform_real<> xyrange(-3.0,3.0);
137  boost::variate_generator< boost::mt19937, boost::uniform_real<> > pos_rand(rng, xyrange);
138  boost::uniform_real<> trange(0, 2 * M_PI);
139  boost::variate_generator< boost::mt19937, boost::uniform_real<> > rot_rand(rng, trange);
140 
141  graph.reset(new FootstepGraph(resolution));
142  //graph->setProgressPublisher(nh, "progress");
143  // set successors
144  std::vector<Eigen::Affine3f> successors;
145  successors.push_back(affineFromXYYaw(0, -0.2, 0));
146  successors.push_back(affineFromXYYaw(0, -0.3, 0));
147  successors.push_back(affineFromXYYaw(0, -0.15, 0));
148  successors.push_back(affineFromXYYaw(0.2, -0.2, 0));
149  successors.push_back(affineFromXYYaw(0.25, -0.2, 0));
150  successors.push_back(affineFromXYYaw(0.1, -0.2, 0));
151  successors.push_back(affineFromXYYaw(-0.1, -0.2, 0));
152  successors.push_back(affineFromXYYaw(0, -0.2, 0.17));
153  successors.push_back(affineFromXYYaw(0, -0.3, 0.17));
154  successors.push_back(affineFromXYYaw(0.2, -0.2, 0.17));
155  successors.push_back(affineFromXYYaw(0.25, -0.2, 0.17));
156  successors.push_back(affineFromXYYaw(0.1, -0.2, 0.17));
157  successors.push_back(affineFromXYYaw(0, -0.2, -0.17));
158  successors.push_back(affineFromXYYaw(0, -0.3, -0.17));
159  successors.push_back(affineFromXYYaw(0.2, -0.2, -0.17));
160  successors.push_back(affineFromXYYaw(0.25, -0.2, -0.17));
161  successors.push_back(affineFromXYYaw(0.1, -0.2, -0.17));
162  FootstepState::Ptr start(new FootstepState(jsk_footstep_msgs::Footstep::LEFT,
163  Eigen::Affine3f::Identity(),
165  resolution));
166  graph->setStartState(start);
167  graph->setBasicSuccessors(successors);
168  jsk_footstep_msgs::FootstepArray ros_start;
169  ros_start.header.frame_id = "odom";
170  ros_start.header.stamp = ros::Time::now();
171  ros_start.footsteps.push_back(*start->toROSMsg());
172  pub_start.publish(ros_start);
173  interactive_markers::InteractiveMarkerServer server("footstep_projection_demo");
174 
175  visualization_msgs::InteractiveMarker int_marker;
176  int_marker.header.frame_id = "/odom";
177  int_marker.header.stamp=ros::Time::now();
178  int_marker.name = "footstep marker";
179 
180  visualization_msgs::InteractiveMarkerControl control;
181 
182  control.orientation.w = 1;
183  control.orientation.x = 1;
184  control.orientation.y = 0;
185  control.orientation.z = 0;
186  // control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
187  // int_marker.controls.push_back(control);
188  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
189  int_marker.controls.push_back(control);
190 
191  control.orientation.w = 1;
192  control.orientation.x = 0;
193  control.orientation.y = 1;
194  control.orientation.z = 0;
195  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
196  int_marker.controls.push_back(control);
197  // control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
198  // int_marker.controls.push_back(control);
199 
200  control.orientation.w = 1;
201  control.orientation.x = 0;
202  control.orientation.y = 0;
203  control.orientation.z = 1;
204  // control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
205  // int_marker.controls.push_back(control);
206  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
207  int_marker.controls.push_back(control);
208  server.insert(int_marker, &processFeedback);
209  server.applyChanges();
210  //plan(Eigen::Affine3f::Identity() * Eigen::Translation3f(3, 3, 0), graph, pub_path, pub_goal, footstep_size);
211  ros::spin();
212  return 0;
213 }
int main(int argc, char **argv)
virtual void setProfileFunction(ProfileFunction f)
ros::Publisher pub_text
double footstepHeuristicStepCost(SolverNode< FootstepState, FootstepGraph >::Ptr node, FootstepGraph::Ptr graph, double first_rotation_weight, double second_rotation_weight)
ros::Publisher pub_goal
path
void publish(const boost::shared_ptr< M > &message) const
end
Eigen::Affine3f affineFromXYYaw(double x, double y, double yaw)
Definition: util.h:42
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
virtual FootstepStateDiscreteCloseList getCloseList()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
const Eigen::Vector3f resolution(0.05, 0.05, 0.08)
server
text
ROSCPP_DECL void spin(Spinner &spinner)
#define M_PI
virtual std::vector< typename SolverNode< State, GraphT >::Ptr > solve(const ros::WallDuration &timeout=ros::WallDuration(1000000000.0))
virtual void setHeuristic(HeuristicFunction h)
Definition: astar_solver.h:71
#define ROS_INFO(...)
string str
FootstepGraph::Ptr graph
start
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher pub_path
const Eigen::Vector3f footstep_size(0.2, 0.1, 0.000001)
INTERACTIVE_MARKERS_PUBLIC void insert(const visualization_msgs::InteractiveMarker &int_marker)
static WallTime now()
INTERACTIVE_MARKERS_PUBLIC void applyChanges()
void profile(FootstepAStarSolver< FootstepGraph > &solver, FootstepGraph::Ptr graph)
static Time now()
void processFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void plan(const Eigen::Affine3f &goal_center, FootstepGraph::Ptr graph, ros::Publisher &pub_path, ros::Publisher &pub_goal, Eigen::Vector3f footstep_size)


jsk_footstep_planner
Author(s): Ryohei Ueda
autogenerated on Fri May 14 2021 02:51:52