footstep_marker.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 
36 #define BOOST_PARAMETER_MAX_ARITY 7
37 #include <iostream>
42 #include <jsk_footstep_msgs/PlanFootstepsGoal.h>
43 #include <jsk_footstep_msgs/PlanFootstepsResult.h>
44 #include <std_srvs/Empty.h>
45 #include <jsk_recognition_msgs/CallSnapIt.h>
46 #include <Eigen/StdVector>
52 #include <jsk_interactive_marker/SnapFootPrint.h>
53 #include <jsk_interactive_marker/SnapFootPrintInput.h>
54 #include <jsk_interactive_marker/SetHeuristic.h>
56 
58 ac_("footstep_planner", true), ac_exec_("footstep_controller", true),
59 plan_run_(false), lleg_first_(true) {
60  // read parameters
62  ros::NodeHandle pnh("~");
63  ros::NodeHandle nh;
64  srv_ = std::make_shared <dynamic_reconfigure::Server<Config> > (pnh);
65  typename dynamic_reconfigure::Server<Config>::CallbackType f =
66  boost::bind (&FootstepMarker::configCallback, this, _1, _2);
67  srv_->setCallback (f);
68  pnh.param("foot_size_x", foot_size_x_, 0.247);
69  pnh.param("foot_size_y", foot_size_y_, 0.135);
70  pnh.param("foot_size_z", foot_size_z_, 0.01);
71  pnh.param("lfoot_frame_id", lfoot_frame_id_, std::string("lfsensor"));
72  pnh.param("rfoot_frame_id", rfoot_frame_id_, std::string("rfsensor"));
73  pnh.param("show_6dof_control", show_6dof_control_, true);
74  // pnh.param("use_projection_service", use_projection_service_, false);
75  // pnh.param("use_projection_topic", use_projection_topic_, false);
76  pnh.param("always_planning", always_planning_, true);
77  // if (use_projection_topic_) {
78  project_footprint_pub_ = pnh.advertise<jsk_interactive_marker::SnapFootPrintInput>("project_footprint", 1);
79  // }
80  // read lfoot_offset
81  readPoseParam(pnh, "lfoot_offset", lleg_offset_);
82  readPoseParam(pnh, "rfoot_offset", rleg_offset_);
83 
84  pnh.param("footstep_margin", footstep_margin_, 0.2);
85  pnh.param("use_footstep_planner", use_footstep_planner_, true);
86 
87  pnh.param("use_footstep_controller", use_footstep_controller_, true);
88  pnh.param("use_initial_footstep_tf", use_initial_footstep_tf_, true);
89  pnh.param("wait_snapit_server", wait_snapit_server_, false);
90  bool nowait = true;
91  pnh.param("no_wait", nowait, true);
92  pnh.param("frame_id", marker_frame_id_, std::string("/map"));
93  footstep_pub_ = nh.advertise<jsk_footstep_msgs::FootstepArray>("footstep_from_marker", 1);
94  snapit_client_ = nh.serviceClient<jsk_recognition_msgs::CallSnapIt>("snapit");
95  snapped_pose_pub_ = pnh.advertise<geometry_msgs::PoseStamped>("snapped_pose", 1);
96  current_pose_pub_ = pnh.advertise<geometry_msgs::PoseStamped>("current_pose", 1);
97  estimate_occlusion_client_ = nh.serviceClient<std_srvs::Empty>("require_estimation");
98  if (!nowait && wait_snapit_server_) {
99  snapit_client_.waitForExistence();
100  }
101 
102  if (pnh.getParam("initial_reference_frame", initial_reference_frame_)) {
103  use_initial_reference_ = true;
104  ROS_INFO_STREAM("initial_reference_frame: " << initial_reference_frame_);
105  }
106  else {
107  use_initial_reference_ = false;
108  ROS_INFO("initial_reference_frame is not specified ");
109  }
110 
112  // menu_handler_.insert( "Snap Legs",
113  // boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
114  // menu_handler_.insert( "Reset Legs",
115  // boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
116  menu_handler_.insert( "Look Ground",
117  boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
118  menu_handler_.insert( "Execute the Plan",
119  boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
120  menu_handler_.insert( "Force to replan",
121  boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
122  // menu_handler_.insert( "Estimate occlusion",
123  // boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
124  menu_handler_.insert( "Cancel Walk",
125  boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
126  menu_handler_.insert( "Toggle 6dof marker",
127  boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
128  // menu_handler_.insert( "Resume Footstep",
129  // boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
130  menu_handler_.insert("Straight Heuristic",
131  boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
132  menu_handler_.insert("Stepcost Heuristic**",
133  boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
134  menu_handler_.insert("LLeg First",
135  boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
136  menu_handler_.insert("RLeg First",
137  boost::bind(&FootstepMarker::menuFeedbackCB, this, _1));
138  marker_pose_.header.frame_id = marker_frame_id_;
139  marker_pose_.header.stamp = ros::Time::now();
140  marker_pose_.pose.orientation.w = 1.0;
141 
142  resetLegPoses();
143 
144  // initialize lleg_initial_pose, rleg_initial_pose
145  lleg_initial_pose_.position.y = footstep_margin_ / 2.0;
146  lleg_initial_pose_.orientation.w = 1.0;
147  rleg_initial_pose_.position.y = - footstep_margin_ / 2.0;
148  rleg_initial_pose_.orientation.w = 1.0;
149 
151  while (ros::ok()) {
152  try {
154  ros::Time(0.0), ros::Duration(10.0))) {
155  ROS_INFO_THROTTLE(1.0,
156  "waiting for transform %s => %s", marker_frame_id_.c_str(),
157  initial_reference_frame_.c_str());
158  continue;
159  }
160  ROS_INFO("resolved transform %s => %s", marker_frame_id_.c_str(),
161  initial_reference_frame_.c_str());
162  tf::StampedTransform transform;
164  ros::Time(0), transform);
165  marker_pose_.pose.position.x = transform.getOrigin().x();
166  marker_pose_.pose.position.y = transform.getOrigin().y();
167  marker_pose_.pose.position.z = transform.getOrigin().z();
168  marker_pose_.pose.orientation.x = transform.getRotation().x();
169  marker_pose_.pose.orientation.y = transform.getRotation().y();
170  marker_pose_.pose.orientation.z = transform.getRotation().z();
171  marker_pose_.pose.orientation.w = transform.getRotation().w();
172  break;
173  }
174  catch (tf2::TransformException& e) {
175  ROS_ERROR("Failed to lookup transformation: %s", e.what());
176  }
177  }
178  }
179 
181 
182  if (use_footstep_planner_) {
183  ROS_INFO("waiting planner server...");
184  ac_.waitForServer();
185  ROS_INFO("found planner server...");
186  }
188  ROS_INFO("waiting controller server...");
190  ROS_INFO("found controller server...");
191  }
192 
193  move_marker_sub_ = nh.subscribe("move_marker", 1, &FootstepMarker::moveMarkerCB, this);
194  menu_command_sub_ = nh.subscribe("menu_command", 1, &FootstepMarker::menuCommandCB, this);
195  exec_sub_ = pnh.subscribe("execute", 1, &FootstepMarker::executeCB, this);
196  resume_sub_ = pnh.subscribe("resume", 1, &FootstepMarker::resumeCB, this);
199  // waiting TF
200  while (ros::ok()) {
201  try {
202  if (tf_listener_->waitForTransform(lfoot_frame_id_, marker_frame_id_,
203  ros::Time(0.0), ros::Duration(10.0))
204  && tf_listener_->waitForTransform(rfoot_frame_id_, marker_frame_id_,
205  ros::Time(0.0), ros::Duration(10.0))) {
206  break;
207  }
208  ROS_INFO("waiting for transform {%s, %s} => %s", lfoot_frame_id_.c_str(),
209  rfoot_frame_id_.c_str(), marker_frame_id_.c_str());
210  }
211  catch (tf2::TransformException& e) {
212  ROS_ERROR("Failed to lookup transformation: %s", e.what());
213  }
214  }
215  ROS_INFO("resolved transform {%s, %s} => %s", lfoot_frame_id_.c_str(),
216  rfoot_frame_id_.c_str(), marker_frame_id_.c_str());
217  }
218  // if (use_projection_topic_) {
219  projection_sub_ = pnh.subscribe("projected_pose", 1,
221  // }
222 }
223 
224 void FootstepMarker::configCallback(Config& config, uint32_t level)
225 {
226  boost::mutex::scoped_lock lock(plane_mutex_);
227  use_projection_topic_ = config.use_projection_topic;
228  use_projection_service_ = config.use_projection_service;
229  use_plane_snap_ = config.use_plane_snap;
230  use_2d_ = config.use_2d;
231 }
232 
233 // a function to read double value from XmlRpcValue.
234 // if the value is integer like 0 and 1, we need to
235 // cast it to int first, and after that, casting to double.
237  switch(val.getType()) {
239  return (double)((int)val);
241  return (double)val;
242  default:
243  return 0;
244  }
245 }
246 
247 void FootstepMarker::readPoseParam(ros::NodeHandle& pnh, const std::string param,
248  tf::Transform& offset) {
250  geometry_msgs::Pose pose;
251  if (pnh.hasParam(param)) {
252  pnh.param(param, v, v);
253  // check if v is 7 length Array
255  v.size() == 7) {
256  // safe parameter access by getXMLDoubleValue
257  pose.position.x = getXMLDoubleValue(v[0]);
258  pose.position.y = getXMLDoubleValue(v[1]);
259  pose.position.z = getXMLDoubleValue(v[2]);
260  pose.orientation.x = getXMLDoubleValue(v[3]);
261  pose.orientation.y = getXMLDoubleValue(v[4]);
262  pose.orientation.z = getXMLDoubleValue(v[5]);
263  pose.orientation.w = getXMLDoubleValue(v[6]);
264  // converst the message as following: msg -> eigen -> tf
265  //void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e);
266  Eigen::Affine3d e;
267  tf::poseMsgToEigen(pose, e); // msg -> eigen
268  tf::transformEigenToTF(e, offset); // eigen -> tf
269  }
270  else {
271  ROS_ERROR_STREAM(param << " is malformed, which should be 7 length array");
272  }
273  }
274  else {
275  ROS_WARN_STREAM("there is no parameter on " << param);
276  }
277 }
278 
280  lleg_pose_.orientation.x = 0.0;
281  lleg_pose_.orientation.y = 0.0;
282  lleg_pose_.orientation.z = 0.0;
283  lleg_pose_.orientation.w = 1.0;
284  lleg_pose_.position.x = 0.0;
285  lleg_pose_.position.y = footstep_margin_ / 2.0;
286  lleg_pose_.position.z = 0.0;
287 
288  rleg_pose_.orientation.x = 0.0;
289  rleg_pose_.orientation.y = 0.0;
290  rleg_pose_.orientation.z = 0.0;
291  rleg_pose_.orientation.w = 1.0;
292  rleg_pose_.position.x = 0.0;
293  rleg_pose_.position.y = - footstep_margin_ / 2.0;
294  rleg_pose_.position.z = 0.0;
295 }
296 
297 geometry_msgs::Pose FootstepMarker::computeLegTransformation(uint8_t leg) {
298  geometry_msgs::Pose new_pose;
299  jsk_recognition_msgs::CallSnapIt srv;
300  srv.request.request.header.stamp = ros::Time::now();
301  srv.request.request.header.frame_id = marker_frame_id_;
302  srv.request.request.target_plane.header.stamp = ros::Time::now();
303  srv.request.request.target_plane.header.frame_id = marker_frame_id_;
304  srv.request.request.target_plane.polygon = computePolygon(leg);
305  if (snapit_client_.call(srv)) {
306  Eigen::Affine3d A, T, B, B_prime;
307  tf::poseMsgToEigen(srv.response.transformation, T);
309  if (leg == jsk_footstep_msgs::Footstep::LEFT) {
311  }
312  else if (leg == jsk_footstep_msgs::Footstep::RIGHT) {
314  }
315  B_prime = A.inverse() * T * A * B;
316  tf::poseEigenToMsg(B_prime, new_pose);
317  }
318  else {
319  // throw exception
320  ROS_ERROR("failed to call snapit");
321  }
322  return new_pose;
323 }
324 
326  geometry_msgs::Pose l_pose = computeLegTransformation(jsk_footstep_msgs::Footstep::LEFT);
327  geometry_msgs::Pose r_pose = computeLegTransformation(jsk_footstep_msgs::Footstep::RIGHT);
328 
329  lleg_pose_ = l_pose;
330  rleg_pose_ = r_pose;
331 
332 }
333 
334 geometry_msgs::Polygon FootstepMarker::computePolygon(uint8_t leg) {
335  geometry_msgs::Polygon polygon;
336  // tree
337  // marker_frame_id_ ---[marker_pose_]---> [leg_pose_] --> points
338  std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > points;
339  points.push_back(Eigen::Vector3d(foot_size_x_ / 2.0, foot_size_y_ / 2.0, 0.0));
340  points.push_back(Eigen::Vector3d(-foot_size_x_ / 2.0, foot_size_y_ / 2.0, 0.0));
341  points.push_back(Eigen::Vector3d(-foot_size_x_ / 2.0, -foot_size_y_ / 2.0, 0.0));
342  points.push_back(Eigen::Vector3d(foot_size_x_ / 2.0, -foot_size_y_ / 2.0, 0.0));
343 
344  Eigen::Affine3d marker_pose_eigen;
345  Eigen::Affine3d leg_pose_eigen;
346  tf::poseMsgToEigen(marker_pose_.pose, marker_pose_eigen);
347  if (leg == jsk_footstep_msgs::Footstep::LEFT) {
348  tf::poseMsgToEigen(lleg_pose_, leg_pose_eigen);
349  }
350  else if (leg == jsk_footstep_msgs::Footstep::RIGHT) {
351  tf::poseMsgToEigen(rleg_pose_, leg_pose_eigen);
352  }
353 
354  for (size_t i = 0; i < points.size(); i++) {
355  Eigen::Vector3d point = points[i];
356  Eigen::Vector3d new_point = marker_pose_eigen * leg_pose_eigen * point;
357  geometry_msgs::Point32 point_msg;
358  point_msg.x = new_point[0];
359  point_msg.y = new_point[1];
360  point_msg.z = new_point[2];
361  polygon.points.push_back(point_msg);
362  }
363 
364  return polygon;
365 }
366 
367 void FootstepMarker::executeCB(const std_msgs::Empty::ConstPtr& msg) {
368  executeFootstep();
369 }
370 
371 void FootstepMarker::resumeCB(const std_msgs::Empty::ConstPtr& msg) {
372  resumeFootstep();
373 }
374 
375 void FootstepMarker::menuCommandCB(const std_msgs::UInt8::ConstPtr& msg) {
376  processMenuFeedback(msg->data);
377 }
378 
380  //ROS_INFO("updateInitialFootstep");
381  try {
383  return;
384  }
385  tf::StampedTransform lfoot_transform, rfoot_transform;
386  tf_listener_->lookupTransform(marker_frame_id_, lfoot_frame_id_, ros::Time(0.0), lfoot_transform);
387  tf_listener_->lookupTransform(marker_frame_id_, rfoot_frame_id_, ros::Time(0.0), rfoot_transform);
388 
389  // apply offset
390  // convert like tf -> eigen -> msg
391  Eigen::Affine3d le, re;
392  tf::transformTFToEigen(lfoot_transform * lleg_offset_, le); // tf -> eigen
393  tf::poseEigenToMsg(le, lleg_initial_pose_); // eigen -> msg
394  tf::transformTFToEigen(rfoot_transform * rleg_offset_, re); // tf -> eigen
395  tf::poseEigenToMsg(re, rleg_initial_pose_); // eigen -> msg
396 
397  // we need to move the marker
399  }
400  catch (tf2::TransformException& e) {
401  ROS_ERROR("Failed to lookup transformation: %s", e.what());
402  }
403 }
404 
406 {
407  std_srvs::Empty empty;
408  if (ros::service::call("/lookaround_ground", empty)) {
409  ROS_INFO("Finished to look ground");
410  }
411  else {
412  ROS_ERROR("Failed to look ground");
413  }
414 }
415 
416 bool FootstepMarker::forceToReplan(std_srvs::Empty::Request& req, std_srvs::Empty::Request& res)
417 {
418  planIfPossible();
419  return true;
420 }
421 
422 void FootstepMarker::processMenuFeedback(uint8_t menu_entry_id) {
423  switch (menu_entry_id) {
424  case 1: { // look ground
425  lookGround();
426  break;
427  }
428  case 2: { // execute
429  executeCB(std_msgs::Empty::ConstPtr());
430  break;
431  }
432  case 3: { // replan
433  planIfPossible();
434  break;
435  }
436  case 4: { // cancel walk
437  cancelWalk();
438  break;
439  }
440  case 5: { // toggle 6dof marker
442  break;
443  }
444  case 6: { // toggle 6dof marker
445  changePlannerHeuristic(":straight-heuristic");
446  break;
447  }
448  case 7: { // toggle 6dof marker
449  changePlannerHeuristic(":stepcost-heuristic**");
450  break;
451  }
452  case 8: { // toggle 6dof marker
453  lleg_first_ = true;
454  break;
455  }
456  case 9: { // toggle 6dof marker
457  lleg_first_ = false;
458  break;
459  }
460 
461  default: {
462  break;
463  }
464  }
465 }
466 
467 void FootstepMarker::changePlannerHeuristic(const std::string& heuristic)
468 {
469  jsk_interactive_marker::SetHeuristic heuristic_req;
470  heuristic_req.request.heuristic = heuristic;
471  if (!ros::service::call("/footstep_planner/set_heuristic", heuristic_req)) {
472  ROS_ERROR("failed to set heuristic");
473  }
474  else {
475  ROS_INFO("Success to set heuristic: %s", heuristic.c_str());
476  }
477 }
478 
480 {
481  ROS_WARN("canceling walking");
483  ROS_WARN("canceled walking");
484 }
485 
487 {
488  std_srvs::Empty srv;
490 }
491 
493 {
495  jsk_interactive_marker::SnapFootPrint snap;
496  snap.request.input_pose = marker_pose_;
497  snap.request.lleg_pose.orientation.w = 1.0;
498  snap.request.rleg_pose.orientation.w = 1.0;
499  snap.request.lleg_pose.position.y = footstep_margin_ / 2.0;
500  snap.request.rleg_pose.position.y = - footstep_margin_ / 2.0;
501  if (ros::service::call("project_footprint", snap) && snap.response.success) {
502  // Resolve tf
503  geometry_msgs::PoseStamped resolved_pose;
504  tf_listener_->transformPose(marker_pose_.header.frame_id,
505  snap.response.snapped_pose,
506  resolved_pose);
507  // Check distance to project
508  Eigen::Vector3d projected_point, marker_point;
509  tf::pointMsgToEigen(marker_pose_.pose.position, marker_point);
510  tf::pointMsgToEigen(resolved_pose.pose.position, projected_point);
511  if ((projected_point - marker_point).norm() < 0.3) {
512  server_->setPose("footstep_marker", resolved_pose.pose);
513  snapped_pose_pub_.publish(resolved_pose);
514  current_pose_pub_.publish(resolved_pose);
515  server_->applyChanges();
516  marker_pose_.pose = resolved_pose.pose;
517  return true;
518  }
519  else {
520  return false;
521  }
522  }
523  else {
524  ROS_WARN("Failed to snap footprint");
525  return false;
526  }
527  }
528  else if (use_projection_topic_) {
529  jsk_interactive_marker::SnapFootPrintInput msg;
530  msg.input_pose = marker_pose_;
531  msg.lleg_pose.orientation.w = 1.0;
532  msg.rleg_pose.orientation.w = 1.0;
533  msg.lleg_pose.position.y = footstep_margin_ / 2.0;
534  msg.rleg_pose.position.y = - footstep_margin_ / 2.0;
536  return true; // true...?
537  }
538 }
539 
540 void FootstepMarker::menuFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
541  processMenuFeedback(feedback->menu_entry_id);
542 }
543 
544 void FootstepMarker::processFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
545  boost::mutex::scoped_lock lock(plane_mutex_);
546 
547  marker_pose_.header = feedback->header;
548  marker_pose_.pose = feedback->pose;
549  marker_frame_id_ = feedback->header.frame_id;
550  bool skip_plan = false;
551  geometry_msgs::PoseStamped input_pose;
553  try {
554  if (feedback->event_type == visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP) {
555  if (use_plane_snap_) {
556  skip_plan = !projectMarkerToPlane();
557  }
558  }
559  if (feedback->event_type == visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP && !skip_plan) {
561  }
562  }
563  catch (tf2::TransformException& e) {
564  ROS_ERROR("Failed to lookup transformation: %s", e.what());
565  }
566 }
567 
570  return;
571  }
573  if (!state.isDone()) {
574  ROS_ERROR("still executing footstep");
575  return;
576  }
577  jsk_footstep_msgs::ExecFootstepsGoal goal;
578  goal.strategy = jsk_footstep_msgs::ExecFootstepsGoal::RESUME;
579  ac_exec_.sendGoal(goal);
580 }
581 
582 void FootstepMarker::projectionCallback(const geometry_msgs::PoseStamped& pose)
583 {
584  geometry_msgs::PoseStamped resolved_pose;
585  tf_listener_->transformPose(marker_pose_.header.frame_id,
586  pose,
587  resolved_pose);
588  // Check distance to project
589  Eigen::Vector3d projected_point, marker_point;
590  tf::pointMsgToEigen(marker_pose_.pose.position, marker_point);
591  tf::pointMsgToEigen(resolved_pose.pose.position, projected_point);
592  if ((projected_point - marker_point).norm() < 0.3) {
593  marker_pose_.pose = resolved_pose.pose;
594  snapped_pose_pub_.publish(resolved_pose);
595  current_pose_pub_.publish(resolved_pose);
596  }
597 }
598 
601  return;
602  }
604  if (!state.isDone()) {
605  ROS_ERROR("still executing footstep");
606  return;
607  }
608  if (!plan_result_) {
609  ROS_ERROR("no planner result is available");
610  return;
611  }
612 
613 
614  jsk_footstep_msgs::ExecFootstepsGoal goal;
615  goal.footstep = plan_result_->result;
616  //goal.strategy = jsk_footstep_msgs::ExecFootstepsGoal::DEFAULT_STRATEGY;
617  ROS_INFO("sending goal...");
618  ac_exec_.sendGoal(goal);
619  // ac_exec_.waitForResult();
620  // ROS_INFO("done executing...");
621 }
622 
624  boost::mutex::scoped_lock lock(plan_run_mutex_);
625  // check the status of the ac_
626  if (!use_footstep_planner_) {
627  return; // do nothing
628  }
629  bool call_planner = !plan_run_;
630  if (call_planner) {
631  plan_run_ = true;
632  jsk_footstep_msgs::PlanFootstepsGoal goal;
633  jsk_footstep_msgs::FootstepArray goal_footstep;
634  goal_footstep.header.frame_id = marker_frame_id_;
635  goal_footstep.header.stamp = ros::Time(0.0);
636  jsk_footstep_msgs::Footstep goal_left;
637  goal_left.leg = jsk_footstep_msgs::Footstep::LEFT;
638  goal_left.pose = getFootstepPose(true);
639  goal_left.dimensions.x = foot_size_x_;
640  goal_left.dimensions.y = foot_size_y_;
641  goal_left.dimensions.z = foot_size_z_;
642  jsk_footstep_msgs::Footstep goal_right;
643  goal_right.pose = getFootstepPose(false);
644  goal_right.leg = jsk_footstep_msgs::Footstep::RIGHT;
645  goal_right.dimensions.x = foot_size_x_;
646  goal_right.dimensions.y = foot_size_y_;
647  goal_right.dimensions.z = foot_size_z_;
648  goal_footstep.footsteps.push_back(goal_left);
649  goal_footstep.footsteps.push_back(goal_right);
650  goal.goal_footstep = goal_footstep;
651  jsk_footstep_msgs::FootstepArray initial_footstep;
652  initial_footstep.header.frame_id = marker_frame_id_;
653  initial_footstep.header.stamp = ros::Time(0.0);
654  // TODO: decide initial footstep by tf
655  jsk_footstep_msgs::Footstep initial_left;
656  initial_left.leg = jsk_footstep_msgs::Footstep::LEFT;
657  initial_left.pose = lleg_initial_pose_;
658  initial_left.dimensions.x = foot_size_x_;
659  initial_left.dimensions.y = foot_size_y_;
660  initial_left.dimensions.z = foot_size_z_;
661 
662  jsk_footstep_msgs::Footstep initial_right;
663  initial_right.leg = jsk_footstep_msgs::Footstep::RIGHT;
664  initial_right.pose = rleg_initial_pose_;
665  initial_right.dimensions.x = foot_size_x_;
666  initial_right.dimensions.y = foot_size_y_;
667  initial_right.dimensions.z = foot_size_z_;
668  if (lleg_first_) {
669  initial_footstep.footsteps.push_back(initial_left);
670  initial_footstep.footsteps.push_back(initial_right);
671  }
672  else {
673  initial_footstep.footsteps.push_back(initial_right);
674  initial_footstep.footsteps.push_back(initial_left);
675  }
676  goal.initial_footstep = initial_footstep;
677  ac_.sendGoal(goal, boost::bind(&FootstepMarker::planDoneCB, this, _1, _2));
678  }
679 }
680 
682  const PlanResult::ConstPtr &result)
683 {
684  boost::mutex::scoped_lock lock(plan_run_mutex_);
685  ROS_INFO("planDoneCB");
688  ROS_INFO("planning is finished");
689  plan_run_ = false;
690 }
691 
692 geometry_msgs::Pose FootstepMarker::getFootstepPose(bool leftp) {
693  tf::Vector3 offset(0, 0, 0);
694  if (leftp) {
695  offset[1] = footstep_margin_ / 2.0;
696  }
697  else {
698  offset[1] = - footstep_margin_ / 2.0;
699  }
700  tf::Transform marker_origin;
701  marker_origin.setOrigin(tf::Vector3(marker_pose_.pose.position.x,
702  marker_pose_.pose.position.y,
703  marker_pose_.pose.position.z));
704  marker_origin.setRotation(tf::Quaternion(marker_pose_.pose.orientation.x,
705  marker_pose_.pose.orientation.y,
706  marker_pose_.pose.orientation.z,
707  marker_pose_.pose.orientation.w));
708  tf::Transform offset_trans;
709  offset_trans.setRotation(tf::Quaternion(0, 0, 0, 1.0));
710  offset_trans.setOrigin(offset);
711 
712  tf::Transform footstep_transform = marker_origin * offset_trans;
713  geometry_msgs::Pose ret;
714  ret.position.x = footstep_transform.getOrigin()[0];
715  ret.position.y = footstep_transform.getOrigin()[1];
716  ret.position.z = footstep_transform.getOrigin()[2];
717  ret.orientation.x = footstep_transform.getRotation()[0];
718  ret.orientation.y = footstep_transform.getRotation()[1];
719  ret.orientation.z = footstep_transform.getRotation()[2];
720  ret.orientation.w = footstep_transform.getRotation()[3];
721  return ret;
722 }
723 
724 void FootstepMarker::moveMarkerCB(const geometry_msgs::PoseStamped::ConstPtr& msg) {
725  // move the marker
726  geometry_msgs::PoseStamped transformed_pose;
727  tf_listener_->transformPose(marker_frame_id_, *msg, transformed_pose);
728  geometry_msgs::PoseStamped prev_pose = marker_pose_;
729  marker_pose_ = transformed_pose;
730  bool skip_plan = false;
731  if (use_plane_snap_) {
732  // do something magicalc
733  skip_plan = !projectMarkerToPlane();
734  if (skip_plan) {
735  marker_pose_ = prev_pose;
736  }
737  }
738 
739  // need to solve TF
740  server_->setPose("footstep_marker", transformed_pose.pose);
741  server_->applyChanges();
743  if (!skip_plan) {
744  planIfPossible();
745  }
746 }
747 
748 visualization_msgs::Marker FootstepMarker::makeFootstepMarker(geometry_msgs::Pose pose) {
749  visualization_msgs::Marker marker;
750  marker.type = visualization_msgs::Marker::CUBE;
751  marker.scale.x = foot_size_x_;
752  marker.scale.y = foot_size_y_;
753  marker.scale.z = foot_size_z_;
754  marker.color.a = 1.0;
755  marker.pose = pose;
756  return marker;
757 }
758 
760  visualization_msgs::InteractiveMarker int_marker;
761  int_marker.header.frame_id = marker_frame_id_;
762  //int_marker.header.stamp = ros::Time(0);
763  int_marker.name = "footstep_marker";
764  int_marker.pose = marker_pose_.pose;
765  visualization_msgs::Marker left_box_marker = makeFootstepMarker(lleg_pose_);
766  left_box_marker.color.g = 1.0;
767 
768  visualization_msgs::InteractiveMarkerControl left_box_control;
769  left_box_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
770  left_box_control.always_visible = true;
771  left_box_control.markers.push_back( left_box_marker );
772 
773  int_marker.controls.push_back( left_box_control );
774 
775  visualization_msgs::Marker right_box_marker = makeFootstepMarker(rleg_pose_);
776  right_box_marker.color.r = 1.0;
777 
778  visualization_msgs::InteractiveMarkerControl right_box_control;
779  right_box_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
780  right_box_control.always_visible = true;
781  right_box_control.markers.push_back( right_box_marker );
782 
783  int_marker.controls.push_back( right_box_control );
784  if (show_6dof_control_) {
785  if (use_2d_) {
786  im_helpers::add3Dof2DControl(int_marker, false);
787  }
788  else {
789  im_helpers::add6DofControl(int_marker, false);
790  }
791  }
792 
793  server_->insert(int_marker,
794  boost::bind(&FootstepMarker::processFeedbackCB, this, _1));
795 
796  // initial footsteps
797  visualization_msgs::InteractiveMarker initial_lleg_int_marker;
798  initial_lleg_int_marker.header.frame_id = marker_frame_id_;
799  initial_lleg_int_marker.name = "left_initial_footstep_marker";
800  initial_lleg_int_marker.pose.orientation.w = 1.0;
801  visualization_msgs::Marker initial_left_marker = makeFootstepMarker(lleg_initial_pose_);
802  initial_left_marker.color.g = 1.0;
803 
804  visualization_msgs::InteractiveMarkerControl initial_left_box_control;
805  initial_left_box_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
806  initial_left_box_control.always_visible = true;
807  initial_left_box_control.markers.push_back(initial_left_marker);
808 
809  initial_lleg_int_marker.controls.push_back( initial_left_box_control );
810  server_->insert(initial_lleg_int_marker,
811  boost::bind(&FootstepMarker::processFeedbackCB, this, _1));
812 
813  visualization_msgs::InteractiveMarker initial_rleg_int_marker;
814  initial_rleg_int_marker.header.frame_id = marker_frame_id_;
815  initial_rleg_int_marker.name = "right_initial_footstep_marker";
816  initial_rleg_int_marker.pose.orientation.w = 1.0;
817  visualization_msgs::Marker initial_right_marker = makeFootstepMarker(rleg_initial_pose_);
818  initial_right_marker.color.r = 1.0;
819 
820  visualization_msgs::InteractiveMarkerControl initial_right_box_control;
821  initial_right_box_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
822  initial_right_box_control.always_visible = true;
823  initial_right_box_control.markers.push_back(initial_right_marker);
824 
825  initial_rleg_int_marker.controls.push_back( initial_right_box_control );
826  server_->insert(initial_rleg_int_marker,
827  boost::bind(&FootstepMarker::processFeedbackCB, this, _1));
828 
829  menu_handler_.apply( *server_, "footstep_marker");
830 
831  server_->applyChanges();
832 }
833 
835 }
836 
837 int main(int argc, char** argv) {
838  ros::init(argc, argv, "footstep_marker");
840  ros::Rate r(10.0);
841  while (ros::ok()) {
842  ros::spinOnce();
843  marker.updateInitialFootstep();
844  r.sleep();
845  }
846  return 0;
847 }
std::string rfoot_frame_id_
msg
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void processFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
f
void transformEigenToTF(const Eigen::Affine3d &e, tf::Transform &t)
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
geometry_msgs::Pose lleg_initial_pose_
PlanningActionClient ac_
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
void initializeInteractiveMarker()
bool use_initial_footstep_tf_
void publish(const boost::shared_ptr< M > &message) const
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
ros::Publisher current_pose_pub_
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void callEstimateOcclusion()
pointer T
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
int size() const
ros::Subscriber projection_sub_
bool call(const std::string &service_name, MReq &req, MRes &res)
std::string initial_reference_frame_
std::string marker_frame_id_
std::shared_ptr< interactive_markers::InteractiveMarkerServer > server_
tf::Transform lleg_offset_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
ros::Subscriber resume_sub_
ROSCPP_DECL const std::string & getName()
ros::Publisher footstep_pub_
void menuFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::ServiceServer plan_if_possible_srv_
int main(int argc, char **argv)
Type const & getType() const
geometry_msgs::Pose getFootstepPose(bool leftp)
pose
#define ROS_WARN(...)
interactive_markers::MenuHandler menu_handler_
bool apply(InteractiveMarkerServer &server, const std::string &marker_name)
void projectionCallback(const geometry_msgs::PoseStamped &pose)
geometry_msgs::Pose lleg_pose_
TFSIMD_FORCE_INLINE const tfScalar & x() const
visualization_msgs::Marker makeFootstepMarker(geometry_msgs::Pose pose)
std::shared_ptr< tf::TransformListener > tf_listener_
void resumeCB(const std_msgs::Empty::ConstPtr &msg)
TFSIMD_FORCE_INLINE const tfScalar & z() const
void moveMarkerCB(const geometry_msgs::PoseStamped::ConstPtr &msg)
boost::mutex plane_mutex_
boost::mutex plan_run_mutex_
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
ros::ServiceClient estimate_occlusion_client_
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
TFSIMD_FORCE_INLINE const tfScalar & y() const
state
void pointMsgToEigen(const geometry_msgs::Point &m, Eigen::Vector3d &e)
geometry_msgs::Pose rleg_pose_
ros::Subscriber move_marker_sub_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
srv
geometry_msgs::Pose computeLegTransformation(uint8_t leg)
#define ROS_WARN_STREAM(args)
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void planDoneCB(const actionlib::SimpleClientGoalState &state, const PlanResult::ConstPtr &result)
bool sleep()
ros::ServiceClient snapit_client_
ros::Publisher project_footprint_pub_
B
ros::Subscriber exec_sub_
void menuCommandCB(const std_msgs::UInt8::ConstPtr &msg)
mutex_t * lock
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
std::string lfoot_frame_id_
PlanResult::ConstPtr plan_result_
EntryHandle insert(const std::string &title, const FeedbackCallback &feedback_cb)
#define ROS_INFO_STREAM(args)
Quaternion getRotation() const
void add3Dof2DControl(visualization_msgs::InteractiveMarker &msg, bool fixed=false)
bool getParam(const std::string &key, std::string &s) const
tf::Transform rleg_offset_
void add6DofControl(visualization_msgs::InteractiveMarker &msg, bool fixed=false)
ExecuteActionClient ac_exec_
void configCallback(Config &config, uint32_t level)
geometry_msgs::Pose rleg_initial_pose_
bool forceToReplan(std_srvs::Empty::Request &req, std_srvs::Empty::Request &res)
GLfloat v[8][3]
static Time now()
jsk_interactive_marker::FootstepMarkerConfig Config
#define ROS_INFO_THROTTLE(rate,...)
void processMenuFeedback(uint8_t id)
ros::Subscriber menu_command_sub_
void changePlannerHeuristic(const std::string &heuristic)
geometry_msgs::Polygon computePolygon(uint8_t leg)
SimpleClientGoalState getState() const
bool hasParam(const std::string &key) const
virtual ~FootstepMarker()
#define ROS_ERROR_STREAM(args)
ResultConstPtr getResult() const
void executeCB(const std_msgs::Empty::ConstPtr &msg)
bool use_projection_service_
ros::Publisher snapped_pose_pub_
void updateInitialFootstep()
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
void readPoseParam(ros::NodeHandle &pnh, const std::string param, tf::Transform &offset)
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
double getXMLDoubleValue(XmlRpc::XmlRpcValue val)
bool use_footstep_controller_
std::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
geometry_msgs::PoseStamped marker_pose_


jsk_interactive_marker
Author(s): furuta
autogenerated on Sat Mar 20 2021 03:03:33