planner_2dof_serial_joints.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014-2017, 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 <ros/ros.h>
31 #include <planner_cspace_msgs/PlannerStatus.h>
32 #include <trajectory_msgs/JointTrajectory.h>
33 #include <sensor_msgs/JointState.h>
35 
36 #include <utility>
37 #include <algorithm>
38 #include <string>
39 #include <list>
40 #include <vector>
41 
43 
45 
46 #include <omp.h>
47 
49 {
50 public:
52 
53 private:
56 
61 
64 
66  Astar::Gridmap<char, 0x40> cm_;
67 
69 
70  float euclidCost(const Astar::Vec& v, const Astar::Vecf coef)
71  {
72  auto vc = v;
73  float cost = 0;
74  for (int i = 0; i < as_.getDim(); i++)
75  {
76  cost += fabs(coef[i] * vc[i]);
77  }
78  return cost;
79  }
80  float euclidCost(const Astar::Vec& v)
81  {
82  return euclidCost(v, euclid_cost_coef_);
83  }
84 
85  float freq_;
86  float freq_min_;
87  bool has_goal_;
88  bool has_start_;
89  std::vector<Astar::Vec> search_list_;
91  float weight_cost_;
92  float expand_;
93  float avg_vel_;
95  {
99  };
101 
102  std::string group_;
103 
104  bool debug_aa_;
105 
106  class LinkBody
107  {
108  protected:
109  class Vec3dof
110  {
111  public:
112  float x_;
113  float y_;
114  float th_;
115 
116  float dist(const Vec3dof& b)
117  {
118  return hypotf(b.x_ - x_, b.y_ - y_);
119  }
120  };
121 
122  public:
123  float radius_[2];
124  float vmax_;
125  float length_;
126  std::string name_;
129  float current_th_;
130 
132  {
133  gain_.x_ = 1.0;
134  gain_.y_ = 1.0;
135  gain_.th_ = 1.0;
136  }
137  Vec3dof end(const float th) const
138  {
139  Vec3dof e = origin_;
140  e.x_ += cosf(e.th_ + th * gain_.th_) * length_;
141  e.y_ += sinf(e.th_ + th * gain_.th_) * length_;
142  e.th_ += th;
143  return e;
144  }
145  bool isCollide(const LinkBody b, const float th0, const float th1)
146  {
147  auto end0 = end(th0);
148  auto end1 = b.end(th1);
149  auto& end0r = radius_[1];
150  auto& end1r = b.radius_[1];
151  auto& origin0 = origin_;
152  auto& origin1 = b.origin_;
153  auto& origin0r = radius_[0];
154  auto& origin1r = b.radius_[0];
155 
156  if (end0.dist(end1) < end0r + end1r)
157  return true;
158  if (end0.dist(origin1) < end0r + origin1r)
159  return true;
160  if (end1.dist(origin0) < end1r + origin0r)
161  return true;
162 
163  // add side collision
164 
165  return false;
166  }
167  };
169 
170  planner_cspace_msgs::PlannerStatus status_;
171  sensor_msgs::JointState joint_;
174 
175  void cbJoint(const sensor_msgs::JointState::ConstPtr& msg)
176  {
177  int id[2] = { -1, -1 };
178  for (size_t i = 0; i < msg->name.size(); i++)
179  {
180  if (msg->name[i].compare(links_[0].name_) == 0)
181  id[0] = i;
182  else if (msg->name[i].compare(links_[1].name_) == 0)
183  id[1] = i;
184  }
185  if (id[0] == -1 || id[1] == -1)
186  {
187  ROS_ERROR("joint_state does not contain link group %s.", group_.c_str());
188  return;
189  }
190  links_[0].current_th_ = msg->position[id[0]];
191  links_[1].current_th_ = msg->position[id[1]];
192 
193  if (replan_prev_ + replan_interval_ < ros::Time::now() &&
194  replan_interval_ > ros::Duration(0) &&
195  replan_prev_ != ros::Time(0))
196  {
197  replan();
198  }
199  }
200  std::pair<ros::Duration, std::pair<float, float>> cmd_prev;
201  trajectory_msgs::JointTrajectory traj_prev;
202  int id[2];
203  void cbTrajectory(const trajectory_msgs::JointTrajectory::ConstPtr& msg)
204  {
205  id[0] = -1;
206  id[1] = -1;
207  for (size_t i = 0; i < msg->joint_names.size(); i++)
208  {
209  if (msg->joint_names[i].compare(links_[0].name_) == 0)
210  id[0] = i;
211  else if (msg->joint_names[i].compare(links_[1].name_) == 0)
212  id[1] = i;
213  }
214  if (id[0] == -1 || id[1] == -1)
215  {
216  ROS_ERROR("joint_trajectory does not contains link group %s.", group_.c_str());
217  return;
218  }
219  if (msg->points.size() != 1)
220  {
221  ROS_ERROR("single trajectory point required.");
222  }
223  decltype(cmd_prev) cmd;
224  cmd.first = msg->points[0].time_from_start;
225  cmd.second.first = msg->points[0].positions[id[0]];
226  cmd.second.second = msg->points[0].positions[id[1]];
227  if (cmd_prev == cmd)
228  return;
229  cmd_prev = cmd;
230  traj_prev = *msg;
231  avg_vel_ = -1.0;
232 
233  replan();
234  }
235  void replan()
236  {
237  replan_prev_ = ros::Time::now();
238  if (id[0] == -1 || id[1] == -1)
239  return;
240 
241  Astar::Vecf start(
242  links_[0].current_th_,
243  links_[1].current_th_);
245  static_cast<float>(traj_prev.points[0].positions[id[0]]),
246  static_cast<float>(traj_prev.points[0].positions[id[1]]));
247 
248  ROS_INFO("link %s: %0.3f, %0.3f", group_.c_str(),
249  traj_prev.points[0].positions[id[0]],
250  traj_prev.points[0].positions[id[1]]);
251 
252  ROS_INFO("Start searching");
253  std::list<Astar::Vecf> path;
254  if (makePlan(start, end, path))
255  {
256  ROS_INFO("Trajectory found");
257 
258  if (avg_vel_ < 0)
259  {
260  float pos_sum = 0;
261  for (auto it = path.begin(); it != path.end(); it++)
262  {
263  auto it_next = it;
264  it_next++;
265  if (it_next != path.end())
266  {
267  float diff[2], diff_max;
268  diff[0] = fabs((*it_next)[0] - (*it)[0]);
269  diff[1] = fabs((*it_next)[1] - (*it)[1]);
270  diff_max = std::max(diff[0], diff[1]);
271  pos_sum += diff_max;
272  }
273  }
274  if (traj_prev.points[0].time_from_start <= ros::Duration(0))
275  {
276  avg_vel_ = std::min(links_[0].vmax_, links_[1].vmax_);
277  }
278  else
279  {
280  avg_vel_ = pos_sum / traj_prev.points[0].time_from_start.toSec();
281  if (avg_vel_ > links_[0].vmax_)
282  avg_vel_ = links_[0].vmax_;
283  if (avg_vel_ > links_[1].vmax_)
284  avg_vel_ = links_[1].vmax_;
285  }
286  }
287 
288  trajectory_msgs::JointTrajectory out;
289  out.header = traj_prev.header;
290  out.header.stamp = ros::Time(0);
291  out.joint_names.resize(2);
292  out.joint_names[0] = links_[0].name_;
293  out.joint_names[1] = links_[1].name_;
294  float pos_sum = 0.0;
295  for (auto it = path.begin(); it != path.end(); it++)
296  {
297  if (it == path.begin())
298  continue;
299 
300  trajectory_msgs::JointTrajectoryPoint p;
301  p.positions.resize(2);
302  p.velocities.resize(2);
303 
304  auto it_prev = it;
305  it_prev--;
306  auto it_next = it;
307  it_next++;
308 
309  float diff[2], diff_max;
310  diff[0] = fabs((*it)[0] - (*it_prev)[0]);
311  diff[1] = fabs((*it)[1] - (*it_prev)[1]);
312  diff_max = std::max(diff[0], diff[1]);
313  pos_sum += diff_max;
314 
315  if (it_next == path.end())
316  {
317  p.velocities[0] = 0.0;
318  p.velocities[1] = 0.0;
319  }
320  else
321  {
322  float dir[2], dir_max;
323  switch (point_vel_)
324  {
325  default:
326  case VEL_PREV:
327  dir[0] = ((*it)[0] - (*it_prev)[0]);
328  dir[1] = ((*it)[1] - (*it_prev)[1]);
329  break;
330  case VEL_NEXT:
331  dir[0] = ((*it_next)[0] - (*it)[0]);
332  dir[1] = ((*it_next)[1] - (*it)[1]);
333  break;
334  case VEL_AVG:
335  dir[0] = ((*it_next)[0] - (*it_prev)[0]);
336  dir[1] = ((*it_next)[1] - (*it_prev)[1]);
337  break;
338  }
339  dir_max = std::max(fabs(dir[0]), fabs(dir[1]));
340  float t = dir_max / avg_vel_;
341 
342  p.velocities[0] = dir[0] / t;
343  p.velocities[1] = dir[1] / t;
344  }
345  p.time_from_start = ros::Duration(pos_sum / avg_vel_);
346  p.positions[0] = (*it)[0];
347  p.positions[1] = (*it)[1];
348  out.points.push_back(p);
349  }
350  pub_trajectory_.publish(out);
351  }
352  else
353  {
354  trajectory_msgs::JointTrajectory out;
355  out.header = traj_prev.header;
356  out.header.stamp = ros::Time(0);
357  out.joint_names.resize(2);
358  out.joint_names[0] = links_[0].name_;
359  out.joint_names[1] = links_[1].name_;
360  trajectory_msgs::JointTrajectoryPoint p;
361  p.positions.resize(2);
362  p.positions[0] = links_[0].current_th_;
363  p.positions[1] = links_[1].current_th_;
364  p.velocities.resize(2);
365  out.points.push_back(p);
366  pub_trajectory_.publish(out);
367 
368  ROS_WARN("Trajectory not found");
369  }
370 
371  pub_status_.publish(status_);
372  }
373 
374 public:
375  explicit planner2dofSerialJointsNode(const std::string group_name)
376  : nh_()
377  , pnh_("~")
378  , tfl_(tfbuf_)
379  {
381  group_ = group_name;
382  ros::NodeHandle nh_group("~/" + group_);
383 
384  pub_trajectory_ = neonavigation_common::compat::advertise<trajectory_msgs::JointTrajectory>(
385  nh_, "joint_trajectory",
386  pnh_, "trajectory_out", 1, true);
387  sub_trajectory_ = neonavigation_common::compat::subscribe(
388  nh_, "trajectory_in",
389  pnh_, "trajectory_in", 1, &planner2dofSerialJointsNode::cbTrajectory, this);
391  nh_, "joint_states",
392  pnh_, "joint", 1, &planner2dofSerialJointsNode::cbJoint, this);
393 
394  pub_status_ = nh_group.advertise<planner_cspace_msgs::PlannerStatus>("status", 1, true);
395 
396  nh_group.param("resolution", resolution_, 128);
397  pnh_.param("debug_aa", debug_aa_, false);
398 
399  double interval;
400  pnh_.param("replan_interval", interval, 0.2);
401  replan_interval_ = ros::Duration(interval);
402  replan_prev_ = ros::Time(0);
403 
404  int queue_size_limit;
405  nh_group.param("queue_size_limit", queue_size_limit, 0);
406  as_.setQueueSizeLimit(queue_size_limit);
407 
408  status_.status = planner_cspace_msgs::PlannerStatus::DONE;
409 
410  has_goal_ = false;
411  has_start_ = false;
412 
413  cm_.reset(Astar::Vec(resolution_ * 2, resolution_ * 2));
414  as_.reset(Astar::Vec(resolution_ * 2, resolution_ * 2));
415  cm_.clear(0);
416 
417  nh_group.param("link0_name", links_[0].name_, std::string("link0"));
418  nh_group.param("link0_joint_radius", links_[0].radius_[0], 0.07f);
419  nh_group.param("link0_end_radius", links_[0].radius_[1], 0.07f);
420  nh_group.param("link0_length", links_[0].length_, 0.135f);
421  nh_group.param("link0_x", links_[0].origin_.x_, 0.22f);
422  nh_group.param("link0_y", links_[0].origin_.y_, 0.0f);
423  nh_group.param("link0_th", links_[0].origin_.th_, 0.0f);
424  nh_group.param("link0_gain_th", links_[0].gain_.th_, -1.0f);
425  nh_group.param("link0_vmax", links_[0].vmax_, 0.5f);
426  nh_group.param("link1_name", links_[1].name_, std::string("link1"));
427  nh_group.param("link1_joint_radius", links_[1].radius_[0], 0.07f);
428  nh_group.param("link1_end_radius", links_[1].radius_[1], 0.07f);
429  nh_group.param("link1_length", links_[1].length_, 0.27f);
430  nh_group.param("link1_x", links_[1].origin_.x_, -0.22f);
431  nh_group.param("link1_y", links_[1].origin_.y_, 0.0f);
432  nh_group.param("link1_th", links_[1].origin_.th_, 0.0f);
433  nh_group.param("link1_gain_th", links_[1].gain_.th_, 1.0f);
434  nh_group.param("link1_vmax", links_[1].vmax_, 0.5f);
435 
436  links_[0].current_th_ = 0.0;
437  links_[1].current_th_ = 0.0;
438 
439  ROS_INFO("link group: %s", group_.c_str());
440  ROS_INFO(" - link0: %s", links_[0].name_.c_str());
441  ROS_INFO(" - link1: %s", links_[1].name_.c_str());
442 
443  nh_group.param("link0_coef", euclid_cost_coef_[0], 1.0f);
444  nh_group.param("link1_coef", euclid_cost_coef_[1], 1.5f);
445 
446  nh_group.param("weight_cost", weight_cost_, 4.0f);
447  nh_group.param("expand", 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 = lroundf(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(abs(d[0]), abs(d[1]));
496  int c = floorf(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  for (p[0] = -range; p[0] <= range; p[0]++)
507  {
508  for (p[1] = -range; p[1] <= range; p[1]++)
509  {
510  search_list_.push_back(p);
511  }
512  }
513 
514  int num_threads;
515  nh_group.param("num_threads", num_threads, 1);
516  omp_set_num_threads(num_threads);
517 
518  has_start_ = has_goal_ = true;
519  }
520 
521 private:
523  const int t0, const int t1,
524  float& gt0, float& gt1)
525  {
526  gt0 = (t0 - resolution_) * 2.0 * M_PI / static_cast<float>(resolution_);
527  gt1 = (t1 - resolution_) * 2.0 * M_PI / static_cast<float>(resolution_);
528  }
530  int& t0, int& t1,
531  const float gt0, const float gt1)
532  {
533  t0 = lroundf(gt0 * resolution_ / (2.0 * M_PI)) + resolution_;
534  t1 = lroundf(gt1 * resolution_ / (2.0 * M_PI)) + resolution_;
535  }
537  const Astar::Vec t,
538  Astar::Vecf& gt)
539  {
540  grid2Metric(t[0], t[1], gt[0], gt[1]);
541  }
543  Astar::Vec& t,
544  const Astar::Vecf gt)
545  {
546  metric2Grid(t[0], t[1], gt[0], gt[1]);
547  }
548  bool makePlan(const Astar::Vecf sg, const Astar::Vecf eg, std::list<Astar::Vecf>& path)
549  {
550  Astar::Vec s, e;
551  metric2Grid(s, sg);
552  metric2Grid(e, eg);
553  ROS_INFO("Planning from (%d, %d) to (%d, %d)",
554  s[0], s[1], e[0], e[1]);
555 
556  if (cm_[s] == 100)
557  {
558  ROS_WARN("Path plan failed (current status is in collision)");
559  status_.error = planner_cspace_msgs::PlannerStatus::PATH_NOT_FOUND;
560  return false;
561  }
562  if (cm_[e] == 100)
563  {
564  ROS_WARN("Path plan failed (goal status is in collision)");
565  status_.error = planner_cspace_msgs::PlannerStatus::PATH_NOT_FOUND;
566  return false;
567  }
568  Astar::Vec d = e - s;
569  d.cycle(resolution_, resolution_);
570 
571  if (cbCost(s, e, e, s) >= euclidCost(d))
572  {
573  path.push_back(sg);
574  path.push_back(eg);
575  if (s == e)
576  {
577  replan_prev_ = ros::Time(0);
578  }
579  return true;
580  }
581  std::list<Astar::Vec> path_grid;
582  // const auto ts = std::chrono::high_resolution_clock::now();
583  float cancel = FLT_MAX;
584  if (replan_interval_ >= ros::Duration(0))
585  cancel = replan_interval_.toSec();
586  if (!as_.search(s, e, path_grid,
588  this, std::placeholders::_1, std::placeholders::_2,
589  std::placeholders::_3, std::placeholders::_4),
591  this, std::placeholders::_1, std::placeholders::_2),
593  this, std::placeholders::_1,
594  std::placeholders::_2, std::placeholders::_3),
596  this, std::placeholders::_1),
597  0,
598  cancel,
599  true))
600  {
601  ROS_WARN("Path plan failed (goal unreachable)");
602  status_.error = planner_cspace_msgs::PlannerStatus::PATH_NOT_FOUND;
603  return false;
604  }
605  // const auto tnow = std::chrono::high_resolution_clock::now();
606  // ROS_INFO("Path found (%0.3f sec.)",
607  // std::chrono::duration<float>(tnow - ts).count());
608 
609  bool first = false;
610  Astar::Vec n_prev = s;
611  path.push_back(sg);
612  int i = 0;
613  for (auto& n : path_grid)
614  {
615  if (!first)
616  {
617  first = true;
618  continue;
619  }
620  if (i == 0)
621  ROS_INFO(" next: %d, %d", n[0], n[1]);
622  Astar::Vec n_diff = n - n_prev;
623  n_diff.cycle(resolution_, resolution_);
624  Astar::Vec n2 = n_prev + n_diff;
625  n_prev = n2;
626 
627  Astar::Vecf p;
628  grid2Metric(n2, p);
629  path.push_back(p);
630  i++;
631  }
632  float prec = 2.0 * M_PI / static_cast<float>(resolution_);
633  Astar::Vecf egp = eg;
634  if (egp[0] < 0)
635  egp[0] += ceilf(-egp[0] / M_PI * 2.0) * M_PI * 2.0;
636  if (egp[1] < 0)
637  egp[1] += ceilf(-egp[1] / M_PI * 2.0) * M_PI * 2.0;
638  path.back()[0] += fmod(egp[0] + prec / 2.0, prec) - prec / 2.0;
639  path.back()[1] += fmod(egp[1] + prec / 2.0, prec) - prec / 2.0;
640 
641  if (debug_aa_)
642  {
643  Astar::Vec p;
644  for (p[0] = resolution_ / 2; p[0] < resolution_ * 3 / 2; p[0]++)
645  {
646  for (p[1] = resolution_ / 2; p[1] < resolution_ * 3 / 2; p[1]++)
647  {
648  bool found = false;
649  for (auto& g : path_grid)
650  {
651  if (g == p)
652  found = true;
653  }
654  if (p == s)
655  printf("\033[31ms\033[0m");
656  else if (p == e)
657  printf("\033[31me\033[0m");
658  else if (found)
659  printf("\033[34m*\033[0m");
660  else
661  printf("%d", cm_[p] / 11);
662  }
663  printf("\n");
664  }
665  printf("\n");
666  }
667 
668  return true;
669  }
670  std::vector<Astar::Vec>& cbSearch(
671  const Astar::Vec& p,
672  const Astar::Vec& s, const Astar::Vec& e)
673  {
674  return search_list_;
675  }
676  bool cbProgress(const std::list<Astar::Vec>& path_grid)
677  {
678  return false;
679  }
680  float cbCostEstim(const Astar::Vec& s, const Astar::Vec& e)
681  {
682  const Astar::Vec d = e - s;
683  return euclidCost(d);
684  }
685  float cbCost(const Astar::Vec& s, Astar::Vec& e,
686  const Astar::Vec& v_goal,
687  const Astar::Vec& v_start)
688  {
689  if ((unsigned int)e[0] >= (unsigned int)resolution_ * 2 ||
690  (unsigned int)e[1] >= (unsigned int)resolution_ * 2)
691  return -1;
692  Astar::Vec d = e - s;
693  d.cycle(resolution_, resolution_);
694 
695  float cost = euclidCost(d);
696 
697  float distf = hypotf(static_cast<float>(d[0]), static_cast<float>(d[1]));
698  float v[2], dp[2];
699  int sum = 0;
700  const int dist = distf;
701  distf /= dist;
702  v[0] = s[0];
703  v[1] = s[1];
704  dp[0] = static_cast<float>(d[0]) / dist;
705  dp[1] = static_cast<float>(d[1]) / dist;
706  Astar::Vec pos;
707  for (int i = 0; i < dist; i++)
708  {
709  pos[0] = lroundf(v[0]);
710  pos[1] = lroundf(v[1]);
711  pos.cycleUnsigned(resolution_, resolution_);
712  const auto c = cm_[pos];
713  if (c > 99)
714  return -1;
715  sum += c;
716  v[0] += dp[0];
717  v[1] += dp[1];
718  }
719  cost += sum * weight_cost_ / 100.0;
720  return cost;
721  }
722 };
723 
724 int main(int argc, char* argv[])
725 {
726  ros::init(argc, argv, "planner_2dof_serial_joints");
727  ros::NodeHandle pnh("~");
728 
729  std::vector<std::shared_ptr<planner2dofSerialJointsNode>> jys;
730  int n;
731  pnh.param("num_groups", n, 1);
732  for (int i = 0; i < n; i++)
733  {
734  std::string name;
735  pnh.param("group" + std::to_string(i) + "_name",
736  name, std::string("group") + std::to_string(i));
737  std::shared_ptr<planner2dofSerialJointsNode> jy;
738 
739  jy.reset(new planner2dofSerialJointsNode(name));
740  jys.push_back(jy);
741  }
742 
743  ros::spin();
744 
745  return 0;
746 }
d
void metric2Grid(int &t0, int &t1, const float gt0, const float gt1)
void cycleUnsigned(const int res, const ArgList &...rest)
Definition: cyclic_vec.h:279
void publish(const boost::shared_ptr< M > &message) const
bool makePlan(const Astar::Vecf sg, const Astar::Vecf eg, std::list< Astar::Vecf > &path)
f
XmlRpcServer s
void cbTrajectory(const trajectory_msgs::JointTrajectory::ConstPtr &msg)
CyclicVecFloat< DIM, NONCYCLIC > Vecf
Definition: grid_astar.h:55
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)
constexpr int getDim() const
Definition: grid_astar.h:123
void setQueueSizeLimit(const size_t size)
Definition: grid_astar.h:153
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())
bool cbProgress(const std::list< Astar::Vec > &path_grid)
bool isCollide(const LinkBody b, const float th0, const float th1)
float cbCostEstim(const Astar::Vec &s, const Astar::Vec &e)
#define ROS_WARN(...)
geometry_msgs::TransformStamped t
ROSCPP_DECL void spin(Spinner &spinner)
void grid2Metric(const int t0, const int t1, float &gt0, float &gt1)
planner_cspace_msgs::PlannerStatus status_
std::vector< Astar::Vec > & cbSearch(const Astar::Vec &p, const Astar::Vec &s, const Astar::Vec &e)
int main(int argc, char *argv[])
bool search(const Vec &s, const Vec &e, std::list< Vec > &path, std::function< float(const Vec &, Vec &, const Vec &, const Vec &)> cb_cost, std::function< float(const Vec &, const Vec &)> cb_cost_estim, std::function< std::vector< Vec > &(const Vec &, const Vec &, const Vec &)> cb_search, std::function< bool(const std::list< Vec > &)> cb_progress, const float cost_leave, const float progress_interval, const bool return_best=false)
Definition: grid_astar.h:158
trajectory_msgs::JointTrajectory traj_prev
void grid2Metric(const Astar::Vec t, Astar::Vecf &gt)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Astar::Gridmap< char, 0x40 > cm_
std::pair< ros::Duration, std::pair< float, float > > cmd_prev
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
planner2dofSerialJointsNode(const std::string group_name)
void cbJoint(const sensor_msgs::JointState::ConstPtr &msg)
INLINE Rall1d< T, V, S > abs(const Rall1d< T, V, S > &x)
static Time now()
float euclidCost(const Astar::Vec &v)
void reset(const Vec size)
Definition: grid_astar.h:136
std::vector< Astar::Vec > search_list_
void metric2Grid(Astar::Vec &t, const Astar::Vecf gt)
float cbCost(const Astar::Vec &s, Astar::Vec &e, const Astar::Vec &v_goal, const Astar::Vec &v_start)
#define ROS_ERROR(...)
float euclidCost(const Astar::Vec &v, const Astar::Vecf coef)
void cycle(const int res, const ArgList &...rest)
Definition: cyclic_vec.h:272


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 05:00:13