31 #include <planner_cspace_msgs/PlannerStatus.h> 32 #include <trajectory_msgs/JointTrajectory.h> 33 #include <sensor_msgs/JointState.h> 66 Astar::Gridmap<char, 0x40>
cm_;
74 for (
int i = 0; i < as_.
getDim(); i++)
76 cost += fabs(coef[i] * vc[i]);
118 return hypotf(b.
x_ - x_, b.
y_ - y_);
147 auto end0 =
end(th0);
148 auto end1 = b.
end(th1);
149 auto& end0r = radius_[1];
153 auto& origin0r = radius_[0];
156 if (end0.dist(end1) < end0r + end1r)
158 if (end0.dist(origin1) < end0r + origin1r)
160 if (end1.dist(origin0) < end1r + origin0r)
175 void cbJoint(
const sensor_msgs::JointState::ConstPtr& msg)
177 int id[2] = { -1, -1 };
178 for (
size_t i = 0; i < msg->name.size(); i++)
180 if (msg->name[i].compare(links_[0].
name_) == 0)
182 else if (msg->name[i].compare(links_[1].
name_) == 0)
185 if (
id[0] == -1 ||
id[1] == -1)
187 ROS_ERROR(
"joint_state does not contain link group %s.", group_.c_str());
200 std::pair<ros::Duration, std::pair<float, float>>
cmd_prev;
203 void cbTrajectory(
const trajectory_msgs::JointTrajectory::ConstPtr& msg)
207 for (
size_t i = 0; i < msg->joint_names.size(); i++)
209 if (msg->joint_names[i].compare(links_[0].
name_) == 0)
211 else if (msg->joint_names[i].compare(links_[1].
name_) == 0)
214 if (
id[0] == -1 ||
id[1] == -1)
216 ROS_ERROR(
"joint_trajectory does not contains link group %s.", group_.c_str());
219 if (msg->points.size() != 1)
221 ROS_ERROR(
"single trajectory point required.");
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]];
238 if (
id[0] == -1 ||
id[1] == -1)
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]]));
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]]);
253 std::list<Astar::Vecf> path;
256 ROS_INFO(
"Trajectory found");
261 for (
auto it = path.begin(); it != path.end(); it++)
265 if (it_next != path.end())
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]);
276 avg_vel_ = std::min(links_[0].
vmax_, links_[1].vmax_);
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_;
288 trajectory_msgs::JointTrajectory out;
289 out.header = traj_prev.header;
291 out.joint_names.resize(2);
292 out.joint_names[0] = links_[0].
name_;
293 out.joint_names[1] = links_[1].
name_;
295 for (
auto it = path.begin(); it != path.end(); it++)
297 if (it == path.begin())
300 trajectory_msgs::JointTrajectoryPoint p;
301 p.positions.resize(2);
302 p.velocities.resize(2);
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]);
315 if (it_next == path.end())
317 p.velocities[0] = 0.0;
318 p.velocities[1] = 0.0;
322 float dir[2], dir_max;
327 dir[0] = ((*it)[0] - (*it_prev)[0]);
328 dir[1] = ((*it)[1] - (*it_prev)[1]);
331 dir[0] = ((*it_next)[0] - (*it)[0]);
332 dir[1] = ((*it_next)[1] - (*it)[1]);
335 dir[0] = ((*it_next)[0] - (*it_prev)[0]);
336 dir[1] = ((*it_next)[1] - (*it_prev)[1]);
339 dir_max = std::max(fabs(dir[0]), fabs(dir[1]));
342 p.velocities[0] = dir[0] / t;
343 p.velocities[1] = dir[1] / t;
346 p.positions[0] = (*it)[0];
347 p.positions[1] = (*it)[1];
348 out.points.push_back(p);
354 trajectory_msgs::JointTrajectory out;
355 out.header = traj_prev.header;
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);
364 p.velocities.resize(2);
365 out.points.push_back(p);
384 pub_trajectory_ = neonavigation_common::compat::advertise<trajectory_msgs::JointTrajectory>(
385 nh_,
"joint_trajectory",
386 pnh_,
"trajectory_out", 1,
true);
388 nh_,
"trajectory_in",
394 pub_status_ = nh_group.
advertise<planner_cspace_msgs::PlannerStatus>(
"status", 1,
true);
396 nh_group.
param(
"resolution", resolution_, 128);
397 pnh_.param(
"debug_aa", debug_aa_,
false);
400 pnh_.param(
"replan_interval", interval, 0.2);
404 int queue_size_limit;
405 nh_group.
param(
"queue_size_limit", queue_size_limit, 0);
408 status_.status = planner_cspace_msgs::PlannerStatus::DONE;
413 cm_.reset(
Astar::Vec(resolution_ * 2, resolution_ * 2));
417 nh_group.
param(
"link0_name", links_[0].
name_, std::string(
"link0"));
418 nh_group.
param(
"link0_joint_radius", links_[0].
radius_[0], 0.07
f);
419 nh_group.
param(
"link0_end_radius", links_[0].radius_[1], 0.07
f);
425 nh_group.
param(
"link0_vmax", links_[0].
vmax_, 0.5
f);
426 nh_group.
param(
"link1_name", links_[1].name_, std::string(
"link1"));
427 nh_group.
param(
"link1_joint_radius", links_[1].radius_[0], 0.07
f);
428 nh_group.
param(
"link1_end_radius", links_[1].radius_[1], 0.07
f);
429 nh_group.
param(
"link1_length", links_[1].length_, 0.27
f);
434 nh_group.
param(
"link1_vmax", links_[1].vmax_, 0.5
f);
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());
443 nh_group.
param(
"link0_coef", euclid_cost_coef_[0], 1.0
f);
444 nh_group.
param(
"link1_coef", euclid_cost_coef_[1], 1.5
f);
446 nh_group.
param(
"weight_cost", weight_cost_, 4.0
f);
447 nh_group.
param(
"expand", expand_, 0.1
f);
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)
454 else if (point_vel_mode.compare(
"next") == 0)
456 else if (point_vel_mode.compare(
"avg") == 0)
459 ROS_ERROR(
"point_vel_mode must be prev/next/avg");
461 ROS_INFO(
"Resolution: %d", resolution_);
463 for (p[0] = 0; p[0] < resolution_ * 2; p[0]++)
465 for (p[1] = 0; p[1] < resolution_ * 2; p[1]++)
470 if (links_[0].
isCollide(links_[1], pf[0], pf[1]))
478 for (p[0] = 0; p[0] < resolution_ * 2; p[0]++)
480 for (p[1] = 0; p[1] < resolution_ * 2; p[1]++)
486 int range = lroundf(expand_ * resolution_ / (2.0 * M_PI));
487 for (d[0] = -range; d[0] <= range; d[0]++)
489 for (d[1] = -range; d[1] <= range; d[1]++)
492 if ((
unsigned int)p2[0] >= (
unsigned int)resolution_ * 2 ||
493 (
unsigned int)p2[1] >= (
unsigned int)resolution_ * 2)
496 int c = floorf(100.0 * (range - dist) / range);
505 nh_group.
param(
"range", range, 8);
506 for (p[0] = -range; p[0] <= range; p[0]++)
508 for (p[1] = -range; p[1] <= range; p[1]++)
510 search_list_.push_back(p);
515 nh_group.
param(
"num_threads", num_threads, 1);
516 omp_set_num_threads(num_threads);
518 has_start_ = has_goal_ =
true;
523 const int t0,
const int t1,
524 float& gt0,
float& gt1)
526 gt0 = (t0 -
resolution_) * 2.0 * M_PI / static_cast<float>(resolution_);
527 gt1 = (t1 -
resolution_) * 2.0 * M_PI / static_cast<float>(resolution_);
531 const float gt0,
const float gt1)
533 t0 = lroundf(gt0 * resolution_ / (2.0 * M_PI)) +
resolution_;
534 t1 = lroundf(gt1 * resolution_ / (2.0 * M_PI)) +
resolution_;
553 ROS_INFO(
"Planning from (%d, %d) to (%d, %d)",
554 s[0], s[1], e[0], e[1]);
558 ROS_WARN(
"Path plan failed (current status is in collision)");
559 status_.error = planner_cspace_msgs::PlannerStatus::PATH_NOT_FOUND;
564 ROS_WARN(
"Path plan failed (goal status is in collision)");
565 status_.error = planner_cspace_msgs::PlannerStatus::PATH_NOT_FOUND;
569 d.
cycle(resolution_, resolution_);
581 std::list<Astar::Vec> path_grid;
583 float cancel = FLT_MAX;
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),
601 ROS_WARN(
"Path plan failed (goal unreachable)");
602 status_.error = planner_cspace_msgs::PlannerStatus::PATH_NOT_FOUND;
613 for (
auto& n : path_grid)
621 ROS_INFO(
" next: %d, %d", n[0], n[1]);
623 n_diff.
cycle(resolution_, resolution_);
632 float prec = 2.0 * M_PI /
static_cast<float>(
resolution_);
635 egp[0] += ceilf(-egp[0] / M_PI * 2.0) * M_PI * 2.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;
644 for (p[0] = resolution_ / 2; p[0] < resolution_ * 3 / 2; p[0]++)
646 for (p[1] = resolution_ / 2; p[1] < resolution_ * 3 / 2; p[1]++)
649 for (
auto& g : path_grid)
655 printf(
"\033[31ms\033[0m");
657 printf(
"\033[31me\033[0m");
659 printf(
"\033[34m*\033[0m");
661 printf(
"%d", cm_[p] / 11);
689 if ((
unsigned int)e[0] >= (
unsigned int)resolution_ * 2 ||
690 (
unsigned int)e[1] >= (
unsigned int)resolution_ * 2)
693 d.
cycle(resolution_, resolution_);
697 float distf = hypotf(static_cast<float>(d[0]), static_cast<float>(d[1]));
700 const int dist = distf;
704 dp[0] =
static_cast<float>(d[0]) / dist;
705 dp[1] =
static_cast<float>(d[1]) / dist;
707 for (
int i = 0; i <
dist; i++)
709 pos[0] = lroundf(v[0]);
710 pos[1] = lroundf(v[1]);
712 const auto c = cm_[pos];
719 cost += sum * weight_cost_ / 100.0;
724 int main(
int argc,
char* argv[])
726 ros::init(argc, argv,
"planner_2dof_serial_joints");
729 std::vector<std::shared_ptr<planner2dofSerialJointsNode>> jys;
731 pnh.
param(
"num_groups", n, 1);
732 for (
int i = 0; i < n; i++)
735 pnh.
param(
"group" + std::to_string(i) +
"_name",
736 name, std::string(
"group") + std::to_string(i));
737 std::shared_ptr<planner2dofSerialJointsNode> jy;
void metric2Grid(int &t0, int &t1, const float gt0, const float gt1)
void cycleUnsigned(const int res, const ArgList &...rest)
void publish(const boost::shared_ptr< M > &message) const
bool makePlan(const Astar::Vecf sg, const Astar::Vecf eg, std::list< Astar::Vecf > &path)
ros::Subscriber sub_joint_
void cbTrajectory(const trajectory_msgs::JointTrajectory::ConstPtr &msg)
CyclicVecFloat< DIM, NONCYCLIC > Vecf
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)
float dist(const Vec3dof &b)
constexpr int getDim() const
void setQueueSizeLimit(const size_t size)
tf2_ros::TransformListener tfl_
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())
ros::Publisher pub_status_
bool cbProgress(const std::list< Astar::Vec > &path_grid)
bool isCollide(const LinkBody b, const float th0, const float th1)
sensor_msgs::JointState joint_
float cbCostEstim(const Astar::Vec &s, const Astar::Vec &e)
geometry_msgs::TransformStamped t
ROSCPP_DECL void spin(Spinner &spinner)
void grid2Metric(const int t0, const int t1, float >0, float >1)
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)
trajectory_msgs::JointTrajectory traj_prev
void grid2Metric(const Astar::Vec t, Astar::Vecf >)
ros::Subscriber sub_trajectory_
Astar::Vecf euclid_cost_coef_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Astar::Gridmap< char, 0x40 > cm_
std::pair< ros::Duration, std::pair< float, float > > cmd_prev
ros::Publisher pub_trajectory_
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)
ros::Duration replan_interval_
float euclidCost(const Astar::Vec &v)
void reset(const Vec size)
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)
float euclidCost(const Astar::Vec &v, const Astar::Vecf coef)
Vec3dof end(const float th) const
void cycle(const int res, const ArgList &...rest)