planner_2dof_serial_joints.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014-2020, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <algorithm>
31 #include <cmath>
32 #include <limits>
33 #include <list>
34 #include <memory>
35 #include <string>
36 #include <utility>
37 #include <vector>
38 
39 #include <omp.h>
40 
41 #include <ros/ros.h>
42 
43 #include <planner_cspace_msgs/PlannerStatus.h>
44 #include <trajectory_msgs/JointTrajectory.h>
45 #include <sensor_msgs/JointState.h>
47 
50 
52 
53 namespace planner_cspace
54 {
55 namespace planner_2dof_serial_joints
56 {
58 {
59 public:
61  using Ptr = std::shared_ptr<Planner2dofSerialJointsNode>;
62 
63 private:
66 
71 
74 
76  Astar::Gridmap<char, 0x40> cm_;
78 
79  float freq_;
80  float freq_min_;
82  float avg_vel_;
84  {
88  };
90 
91  std::string group_;
92 
93  bool debug_aa_;
94 
95  class LinkBody
96  {
97  protected:
98  class Vec3dof
99  {
100  public:
101  float x_;
102  float y_;
103  float th_;
104 
105  float dist(const Vec3dof& b)
106  {
107  return std::hypot(b.x_ - x_, b.y_ - y_);
108  }
109  };
110 
111  public:
112  float radius_[2];
113  float vmax_;
114  float length_;
115  std::string name_;
118  float current_th_;
119 
121  {
122  gain_.x_ = 1.0;
123  gain_.y_ = 1.0;
124  gain_.th_ = 1.0;
125  }
126  Vec3dof end(const float th) const
127  {
128  Vec3dof e = origin_;
129  e.x_ += cosf(e.th_ + th * gain_.th_) * length_;
130  e.y_ += sinf(e.th_ + th * gain_.th_) * length_;
131  e.th_ += th;
132  return e;
133  }
134  bool isCollide(const LinkBody b, const float th0, const float th1)
135  {
136  auto end0 = end(th0);
137  auto end1 = b.end(th1);
138  auto& end0r = radius_[1];
139  auto& end1r = b.radius_[1];
140  auto& origin0 = origin_;
141  auto& origin1 = b.origin_;
142  auto& origin0r = radius_[0];
143  auto& origin1r = b.radius_[0];
144 
145  if (end0.dist(end1) < end0r + end1r)
146  return true;
147  if (end0.dist(origin1) < end0r + origin1r)
148  return true;
149  if (end1.dist(origin0) < end1r + origin0r)
150  return true;
151 
152  // add side collision
153 
154  return false;
155  }
156  };
158 
159  planner_cspace_msgs::PlannerStatus status_;
160  sensor_msgs::JointState joint_;
164 
165  void cbJoint(const sensor_msgs::JointState::ConstPtr& msg)
166  {
167  int id[2] = {-1, -1};
168  for (size_t i = 0; i < msg->name.size(); i++)
169  {
170  if (msg->name[i].compare(links_[0].name_) == 0)
171  id[0] = i;
172  else if (msg->name[i].compare(links_[1].name_) == 0)
173  id[1] = i;
174  }
175  if (id[0] == -1 || id[1] == -1)
176  {
177  ROS_ERROR("joint_state does not contain link group %s.", group_.c_str());
178  return;
179  }
180  links_[0].current_th_ = msg->position[id[0]];
181  links_[1].current_th_ = msg->position[id[1]];
182  has_joint_states_ = true;
183 
184  if ((replan_prev_ + replan_interval_ < ros::Time::now() ||
185  replan_prev_ == ros::Time(0)) &&
186  replan_interval_ > ros::Duration(0))
187  {
188  replan();
189  }
190  }
191  std::pair<ros::Duration, std::pair<float, float>> cmd_prev_;
192  trajectory_msgs::JointTrajectory traj_prev_;
193  int id_[2];
194  void cbTrajectory(const trajectory_msgs::JointTrajectory::ConstPtr& msg)
195  {
196  id_[0] = -1;
197  id_[1] = -1;
198  for (size_t i = 0; i < msg->joint_names.size(); i++)
199  {
200  if (msg->joint_names[i].compare(links_[0].name_) == 0)
201  id_[0] = i;
202  else if (msg->joint_names[i].compare(links_[1].name_) == 0)
203  id_[1] = i;
204  }
205  if (id_[0] == -1 || id_[1] == -1)
206  {
207  ROS_ERROR("joint_trajectory does not contains link group %s.", group_.c_str());
208  return;
209  }
210  if (msg->points.size() != 1)
211  {
212  ROS_ERROR("single trajectory point required.");
213  }
214  decltype(cmd_prev_) cmd;
215  cmd.first = msg->points[0].time_from_start;
216  cmd.second.first = msg->points[0].positions[id_[0]];
217  cmd.second.second = msg->points[0].positions[id_[1]];
218  if (cmd_prev_ == cmd)
219  return;
220  cmd_prev_ = cmd;
221  traj_prev_ = *msg;
222  avg_vel_ = -1.0;
223 
224  replan();
225  }
226  void replan()
227  {
228  if (!has_joint_states_)
229  return;
230 
231  replan_prev_ = ros::Time::now();
232  if (id_[0] == -1 || id_[1] == -1)
233  return;
234 
236  links_[0].current_th_,
237  links_[1].current_th_);
239  static_cast<float>(traj_prev_.points[0].positions[id_[0]]),
240  static_cast<float>(traj_prev_.points[0].positions[id_[1]]));
241 
242  ROS_INFO("link %s: %0.3f, %0.3f", group_.c_str(),
243  traj_prev_.points[0].positions[id_[0]],
244  traj_prev_.points[0].positions[id_[1]]);
245 
246  status_.status = planner_cspace_msgs::PlannerStatus::DOING;
247  status_.error = planner_cspace_msgs::PlannerStatus::GOING_WELL;
248 
249  ROS_INFO("Start searching");
250  std::list<Astar::Vecf> path;
251  if (makePlan(start, end, path))
252  {
253  ROS_INFO("Trajectory found");
254 
255  if (avg_vel_ < 0)
256  {
257  float pos_sum = 0;
258  for (auto it = path.begin(); it != path.end(); it++)
259  {
260  auto it_next = it;
261  it_next++;
262  if (it_next != path.end())
263  {
264  float diff[2], diff_max;
265  diff[0] = std::abs((*it_next)[0] - (*it)[0]);
266  diff[1] = std::abs((*it_next)[1] - (*it)[1]);
267  diff_max = std::max(diff[0], diff[1]);
268  pos_sum += diff_max;
269  }
270  }
271  if (traj_prev_.points[0].time_from_start <= ros::Duration(0))
272  {
273  avg_vel_ = std::min(links_[0].vmax_, links_[1].vmax_);
274  }
275  else
276  {
277  avg_vel_ = pos_sum / traj_prev_.points[0].time_from_start.toSec();
278  if (avg_vel_ > links_[0].vmax_)
279  avg_vel_ = links_[0].vmax_;
280  if (avg_vel_ > links_[1].vmax_)
281  avg_vel_ = links_[1].vmax_;
282  }
283  }
284 
285  trajectory_msgs::JointTrajectory out;
286  out.header = traj_prev_.header;
287  out.header.stamp = ros::Time(0);
288  out.joint_names.resize(2);
289  out.joint_names[0] = links_[0].name_;
290  out.joint_names[1] = links_[1].name_;
291  float pos_sum = 0.0;
292  for (auto it = path.begin(); it != path.end(); it++)
293  {
294  if (it == path.begin())
295  continue;
296 
297  trajectory_msgs::JointTrajectoryPoint p;
298  p.positions.resize(2);
299  p.velocities.resize(2);
300 
301  auto it_prev = it;
302  it_prev--;
303  auto it_next = it;
304  it_next++;
305 
306  float diff[2], diff_max;
307  diff[0] = std::abs((*it)[0] - (*it_prev)[0]);
308  diff[1] = std::abs((*it)[1] - (*it_prev)[1]);
309  diff_max = std::max(diff[0], diff[1]);
310  pos_sum += diff_max;
311 
312  if (it_next == path.end())
313  {
314  p.velocities[0] = 0.0;
315  p.velocities[1] = 0.0;
316  }
317  else
318  {
319  float dir[2], dir_max;
320  switch (point_vel_)
321  {
322  default:
323  case VEL_PREV:
324  dir[0] = ((*it)[0] - (*it_prev)[0]);
325  dir[1] = ((*it)[1] - (*it_prev)[1]);
326  break;
327  case VEL_NEXT:
328  dir[0] = ((*it_next)[0] - (*it)[0]);
329  dir[1] = ((*it_next)[1] - (*it)[1]);
330  break;
331  case VEL_AVG:
332  dir[0] = ((*it_next)[0] - (*it_prev)[0]);
333  dir[1] = ((*it_next)[1] - (*it_prev)[1]);
334  break;
335  }
336  dir_max = std::max(std::abs(dir[0]), std::abs(dir[1]));
337  float t = dir_max / avg_vel_;
338 
339  p.velocities[0] = dir[0] / t;
340  p.velocities[1] = dir[1] / t;
341  }
342  p.time_from_start = ros::Duration(pos_sum / avg_vel_);
343  p.positions[0] = (*it)[0];
344  p.positions[1] = (*it)[1];
345  out.points.push_back(p);
346  }
347  pub_trajectory_.publish(out);
348  }
349  else
350  {
351  trajectory_msgs::JointTrajectory out;
352  out.header = traj_prev_.header;
353  out.header.stamp = ros::Time(0);
354  out.joint_names.resize(2);
355  out.joint_names[0] = links_[0].name_;
356  out.joint_names[1] = links_[1].name_;
357  trajectory_msgs::JointTrajectoryPoint p;
358  p.positions.resize(2);
359  p.positions[0] = links_[0].current_th_;
360  p.positions[1] = links_[1].current_th_;
361  p.velocities.resize(2);
362  out.points.push_back(p);
363  pub_trajectory_.publish(out);
364 
365  ROS_WARN("Trajectory not found");
366  }
367 
368  status_.header.stamp = ros::Time::now();
369  pub_status_.publish(status_);
370  }
371 
372 public:
373  explicit Planner2dofSerialJointsNode(const std::string group_name)
374  : nh_()
375  , pnh_("~")
376  , tfl_(tfbuf_)
377  , has_joint_states_(false)
378  {
380  group_ = group_name;
381  ros::NodeHandle nh_group("~/" + group_);
382 
383  pub_trajectory_ = neonavigation_common::compat::advertise<trajectory_msgs::JointTrajectory>(
384  nh_, "joint_trajectory",
385  pnh_, "trajectory_out", 1, true);
386  sub_trajectory_ = neonavigation_common::compat::subscribe(
387  nh_, "trajectory_in",
388  pnh_, "trajectory_in", 1, &Planner2dofSerialJointsNode::cbTrajectory, this);
390  nh_, "joint_states",
391  pnh_, "joint", 1, &Planner2dofSerialJointsNode::cbJoint, this);
392 
393  pub_status_ = nh_group.advertise<planner_cspace_msgs::PlannerStatus>("status", 1, true);
394 
395  nh_group.param("resolution", resolution_, 128);
396  pnh_.param("debug_aa", debug_aa_, false);
397 
398  double interval;
399  pnh_.param("replan_interval", interval, 0.2);
400  replan_interval_ = ros::Duration(interval);
401  replan_prev_ = ros::Time(0);
402 
403  int queue_size_limit;
404  nh_group.param("queue_size_limit", queue_size_limit, 0);
405  as_.setQueueSizeLimit(queue_size_limit);
406 
407  status_.status = planner_cspace_msgs::PlannerStatus::DONE;
408 
409  cm_.reset(Astar::Vec(resolution_ * 2, resolution_ * 2));
410  as_.reset(Astar::Vec(resolution_ * 2, resolution_ * 2));
411  cm_.clear(0);
412 
413  nh_group.param("link0_name", links_[0].name_, std::string("link0"));
414  nh_group.param("link0_joint_radius", links_[0].radius_[0], 0.07f);
415  nh_group.param("link0_end_radius", links_[0].radius_[1], 0.07f);
416  nh_group.param("link0_length", links_[0].length_, 0.135f);
417  nh_group.param("link0_x", links_[0].origin_.x_, 0.22f);
418  nh_group.param("link0_y", links_[0].origin_.y_, 0.0f);
419  nh_group.param("link0_th", links_[0].origin_.th_, 0.0f);
420  nh_group.param("link0_gain_th", links_[0].gain_.th_, -1.0f);
421  nh_group.param("link0_vmax", links_[0].vmax_, 0.5f);
422  nh_group.param("link1_name", links_[1].name_, std::string("link1"));
423  nh_group.param("link1_joint_radius", links_[1].radius_[0], 0.07f);
424  nh_group.param("link1_end_radius", links_[1].radius_[1], 0.07f);
425  nh_group.param("link1_length", links_[1].length_, 0.27f);
426  nh_group.param("link1_x", links_[1].origin_.x_, -0.22f);
427  nh_group.param("link1_y", links_[1].origin_.y_, 0.0f);
428  nh_group.param("link1_th", links_[1].origin_.th_, 0.0f);
429  nh_group.param("link1_gain_th", links_[1].gain_.th_, 1.0f);
430  nh_group.param("link1_vmax", links_[1].vmax_, 0.5f);
431 
432  links_[0].current_th_ = 0.0;
433  links_[1].current_th_ = 0.0;
434  id_[0] = -1;
435  id_[1] = -1;
436 
437  ROS_INFO("link group: %s", group_.c_str());
438  ROS_INFO(" - link0: %s", links_[0].name_.c_str());
439  ROS_INFO(" - link1: %s", links_[1].name_.c_str());
440 
441  Astar::Vecf euclid_cost_coef;
442  nh_group.param("link0_coef", euclid_cost_coef[0], 1.0f);
443  nh_group.param("link1_coef", euclid_cost_coef[1], 1.5f);
444 
445  CostCoeff cc;
446  nh_group.param("weight_cost", cc.weight_cost_, 4.0f);
447  nh_group.param("expand", cc.expand_, 0.1f);
448 
449  std::string point_vel_mode;
450  nh_group.param("point_vel_mode", point_vel_mode, std::string("prev"));
451  std::transform(point_vel_mode.begin(), point_vel_mode.end(), point_vel_mode.begin(), ::tolower);
452  if (point_vel_mode.compare("prev") == 0)
453  point_vel_ = VEL_PREV;
454  else if (point_vel_mode.compare("next") == 0)
455  point_vel_ = VEL_NEXT;
456  else if (point_vel_mode.compare("avg") == 0)
457  point_vel_ = VEL_AVG;
458  else
459  ROS_ERROR("point_vel_mode must be prev/next/avg");
460 
461  ROS_INFO("Resolution: %d", resolution_);
462  Astar::Vec p;
463  for (p[0] = 0; p[0] < resolution_ * 2; p[0]++)
464  {
465  for (p[1] = 0; p[1] < resolution_ * 2; p[1]++)
466  {
467  Astar::Vecf pf;
468  grid2Metric(p, pf);
469 
470  if (links_[0].isCollide(links_[1], pf[0], pf[1]))
471  cm_[p] = 100;
472  // else if(pf[0] > M_PI || pf[1] > M_PI)
473  // cm_[p] = 50;
474  else
475  cm_[p] = 0;
476  }
477  }
478  for (p[0] = 0; p[0] < resolution_ * 2; p[0]++)
479  {
480  for (p[1] = 0; p[1] < resolution_ * 2; p[1]++)
481  {
482  if (cm_[p] != 100)
483  continue;
484 
485  Astar::Vec d;
486  int range = std::lround(cc.expand_ * resolution_ / (2.0 * M_PI));
487  for (d[0] = -range; d[0] <= range; d[0]++)
488  {
489  for (d[1] = -range; d[1] <= range; d[1]++)
490  {
491  Astar::Vec p2 = p + d;
492  if ((unsigned int)p2[0] >= (unsigned int)resolution_ * 2 ||
493  (unsigned int)p2[1] >= (unsigned int)resolution_ * 2)
494  continue;
495  int dist = std::max(std::abs(d[0]), abs(d[1]));
496  int c = std::floor(100.0 * (range - dist) / range);
497  if (cm_[p2] < c)
498  cm_[p2] = c;
499  }
500  }
501  }
502  }
503 
504  int range;
505  nh_group.param("range", range, 8);
506 
507  model_.reset(new GridAstarModel2DoFSerialJoint(
508  euclid_cost_coef,
509  resolution_,
510  cm_,
511  cc,
512  range));
513 
514  int num_threads;
515  nh_group.param("num_threads", num_threads, 1);
516  omp_set_num_threads(num_threads);
517  }
518 
519 private:
521  const int t0, const int t1,
522  float& gt0, float& gt1)
523  {
524  gt0 = (t0 - resolution_) * 2.0 * M_PI / static_cast<float>(resolution_);
525  gt1 = (t1 - resolution_) * 2.0 * M_PI / static_cast<float>(resolution_);
526  }
528  int& t0, int& t1,
529  const float gt0, const float gt1)
530  {
531  t0 = std::lround(gt0 * resolution_ / (2.0 * M_PI)) + resolution_;
532  t1 = std::lround(gt1 * resolution_ / (2.0 * M_PI)) + resolution_;
533  }
535  const Astar::Vec t,
536  Astar::Vecf& gt)
537  {
538  grid2Metric(t[0], t[1], gt[0], gt[1]);
539  }
541  Astar::Vec& t,
542  const Astar::Vecf gt)
543  {
544  metric2Grid(t[0], t[1], gt[0], gt[1]);
545  }
546  bool makePlan(const Astar::Vecf sg, const Astar::Vecf eg, std::list<Astar::Vecf>& path)
547  {
548  Astar::Vec s, e;
549  metric2Grid(s, sg);
550  metric2Grid(e, eg);
551  ROS_INFO("Planning from (%d, %d) to (%d, %d)",
552  s[0], s[1], e[0], e[1]);
553 
554  if (cm_[s] == 100)
555  {
556  ROS_WARN("Path plan failed (current status is in collision)");
557  status_.error = planner_cspace_msgs::PlannerStatus::PATH_NOT_FOUND;
558  return false;
559  }
560  if (cm_[e] == 100)
561  {
562  ROS_WARN("Path plan failed (goal status is in collision)");
563  status_.error = planner_cspace_msgs::PlannerStatus::PATH_NOT_FOUND;
564  return false;
565  }
566  Astar::Vec d = e - s;
567  d.cycle(resolution_, resolution_);
568 
569  std::vector<Astar::VecWithCost> starts;
570  starts.emplace_back(s);
571 
572  if (model_->cost(s, e, starts, e) >= model_->euclidCost(d))
573  {
574  path.push_back(sg);
575  path.push_back(eg);
576  if (s == e)
577  {
578  replan_prev_ = ros::Time(0);
579  }
580  return true;
581  }
582  std::list<Astar::Vec> path_grid;
583  // const auto ts = std::chrono::high_resolution_clock::now();
584  float cancel = std::numeric_limits<float>::max();
585  if (replan_interval_ >= ros::Duration(0))
586  cancel = replan_interval_.toSec();
587  if (!as_.search(
588  starts, e, path_grid, model_,
589  std::bind(&Planner2dofSerialJointsNode::cbProgress, this, std::placeholders::_1, std::placeholders::_2),
590  0, cancel, true))
591  {
592  ROS_WARN("Path plan failed (goal unreachable)");
593  status_.error = planner_cspace_msgs::PlannerStatus::PATH_NOT_FOUND;
594  return false;
595  }
596  // const auto tnow = std::chrono::high_resolution_clock::now();
597  // ROS_INFO("Path found (%0.3f sec.)",
598  // std::chrono::duration<float>(tnow - ts).count());
599 
600  bool first = false;
601  Astar::Vec n_prev = s;
602  path.push_back(sg);
603  int i = 0;
604  for (auto& n : path_grid)
605  {
606  if (!first)
607  {
608  first = true;
609  continue;
610  }
611  if (i == 0)
612  ROS_INFO(" next: %d, %d", n[0], n[1]);
613  Astar::Vec n_diff = n - n_prev;
614  n_diff.cycle(resolution_, resolution_);
615  Astar::Vec n2 = n_prev + n_diff;
616  n_prev = n2;
617 
618  Astar::Vecf p;
619  grid2Metric(n2, p);
620  path.push_back(p);
621  i++;
622  }
623  float prec = 2.0 * M_PI / static_cast<float>(resolution_);
624  Astar::Vecf egp = eg;
625  if (egp[0] < 0)
626  egp[0] += std::ceil(-egp[0] / M_PI * 2.0) * M_PI * 2.0;
627  if (egp[1] < 0)
628  egp[1] += std::ceil(-egp[1] / M_PI * 2.0) * M_PI * 2.0;
629  path.back()[0] += fmod(egp[0] + prec / 2.0, prec) - prec / 2.0;
630  path.back()[1] += fmod(egp[1] + prec / 2.0, prec) - prec / 2.0;
631 
632  if (debug_aa_)
633  {
634  Astar::Vec p;
635  for (p[0] = resolution_ / 2; p[0] < resolution_ * 3 / 2; p[0]++)
636  {
637  for (p[1] = resolution_ / 2; p[1] < resolution_ * 3 / 2; p[1]++)
638  {
639  bool found = false;
640  for (auto& g : path_grid)
641  {
642  if (g == p)
643  found = true;
644  }
645  if (p == s)
646  printf("\033[31ms\033[0m");
647  else if (p == e)
648  printf("\033[31me\033[0m");
649  else if (found)
650  printf("\033[34m*\033[0m");
651  else
652  printf("%d", cm_[p] / 11);
653  }
654  printf("\n");
655  }
656  printf("\n");
657  }
658 
659  return true;
660  }
661  bool cbProgress(const std::list<Astar::Vec>& /* path_grid */, const SearchStats& /* stats */)
662  {
663  return false;
664  }
665 };
666 } // namespace planner_2dof_serial_joints
667 } // namespace planner_cspace
668 
669 int main(int argc, char* argv[])
670 {
671  ros::init(argc, argv, "planner_2dof_serial_joints");
672  ros::NodeHandle pnh("~");
673 
674  std::vector<planner_cspace::planner_2dof_serial_joints::Planner2dofSerialJointsNode::Ptr> jys;
675  int n;
676  pnh.param("num_groups", n, 1);
677  for (int i = 0; i < n; i++)
678  {
679  std::string name;
680  pnh.param("group" + std::to_string(i) + "_name",
681  name, std::string("group") + std::to_string(i));
683 
685  jys.push_back(jy);
686  }
687 
688  ros::spin();
689 
690  return 0;
691 }
d
void cbTrajectory(const trajectory_msgs::JointTrajectory::ConstPtr &msg)
void grid2Metric(const int t0, const int t1, float &gt0, float &gt1)
ROSCPP_DECL void start()
f
string cmd
bool search(const std::vector< VecWithCost > &ss, const Vec &e, std::list< Vec > &path, const typename GridAstarModelBase< DIM, NONCYCLIC >::Ptr &model, ProgressCallback cb_progress, const float cost_leave, const float progress_interval, const bool return_best=false)
Definition: grid_astar.h:169
XmlRpcServer s
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
void setQueueSizeLimit(const size_t size)
Definition: grid_astar.h:164
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints())
#define ROS_WARN(...)
geometry_msgs::TransformStamped t
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
int main(int argc, char *argv[])
#define ROS_INFO(...)
void reset(const Vec size)
Definition: grid_astar.h:147
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool cbProgress(const std::list< Astar::Vec > &, const SearchStats &)
ROSCPP_DECL void spin()
INLINE Rall1d< T, V, S > abs(const Rall1d< T, V, S > &x)
static Time now()
void cycle(const int res, const ArgList &... rest)
Definition: cyclic_vec.h:282
#define ROS_ERROR(...)
bool makePlan(const Astar::Vecf sg, const Astar::Vecf eg, std::list< Astar::Vecf > &path)
void metric2Grid(int &t0, int &t1, const float gt0, const float gt1)


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 3 2023 02:39:06