43 #include <planner_cspace_msgs/PlannerStatus.h>
44 #include <trajectory_msgs/JointTrajectory.h>
45 #include <sensor_msgs/JointState.h>
55 namespace planner_2dof_serial_joints
61 using Ptr = std::shared_ptr<Planner2dofSerialJointsNode>;
76 Astar::Gridmap<char, 0x40>
cm_;
107 return std::hypot(b.
x_ -
x_, b.
y_ -
y_);
136 auto end0 =
end(th0);
137 auto end1 = b.
end(th1);
145 if (end0.dist(end1) < end0r + end1r)
147 if (end0.dist(origin1) < end0r + origin1r)
149 if (end1.dist(origin0) < end1r + origin0r)
165 void cbJoint(
const sensor_msgs::JointState::ConstPtr& msg)
167 int id[2] = {-1, -1};
168 for (
size_t i = 0; i <
msg->name.size(); i++)
175 if (
id[0] == -1 ||
id[1] == -1)
177 ROS_ERROR(
"joint_state does not contain link group %s.",
group_.c_str());
191 std::pair<ros::Duration, std::pair<float, float>>
cmd_prev_;
194 void cbTrajectory(
const trajectory_msgs::JointTrajectory::ConstPtr& msg)
198 for (
size_t i = 0; i <
msg->joint_names.size(); i++)
205 if (
id_[0] == -1 ||
id_[1] == -1)
207 ROS_ERROR(
"joint_trajectory does not contains link group %s.",
group_.c_str());
210 if (
msg->points.size() != 1)
212 ROS_ERROR(
"single trajectory point required.");
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]];
232 if (
id_[0] == -1 ||
id_[1] == -1)
246 status_.status = planner_cspace_msgs::PlannerStatus::DOING;
247 status_.error = planner_cspace_msgs::PlannerStatus::GOING_WELL;
250 std::list<Astar::Vecf> path;
258 for (
auto it = path.begin(); it != path.end(); it++)
262 if (it_next != path.end())
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]);
285 trajectory_msgs::JointTrajectory out;
288 out.joint_names.resize(2);
292 for (
auto it = path.begin(); it != path.end(); it++)
294 if (it == path.begin())
297 trajectory_msgs::JointTrajectoryPoint p;
298 p.positions.resize(2);
299 p.velocities.resize(2);
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]);
312 if (it_next == path.end())
314 p.velocities[0] = 0.0;
315 p.velocities[1] = 0.0;
319 float dir[2], dir_max;
324 dir[0] = ((*it)[0] - (*it_prev)[0]);
325 dir[1] = ((*it)[1] - (*it_prev)[1]);
328 dir[0] = ((*it_next)[0] - (*it)[0]);
329 dir[1] = ((*it_next)[1] - (*it)[1]);
332 dir[0] = ((*it_next)[0] - (*it_prev)[0]);
333 dir[1] = ((*it_next)[1] - (*it_prev)[1]);
336 dir_max = std::max(std::abs(dir[0]), std::abs(dir[1]));
339 p.velocities[0] = dir[0] /
t;
340 p.velocities[1] = dir[1] /
t;
343 p.positions[0] = (*it)[0];
344 p.positions[1] = (*it)[1];
345 out.points.push_back(p);
351 trajectory_msgs::JointTrajectory out;
354 out.joint_names.resize(2);
357 trajectory_msgs::JointTrajectoryPoint p;
358 p.positions.resize(2);
361 p.velocities.resize(2);
362 out.points.push_back(p);
383 pub_trajectory_ = neonavigation_common::compat::advertise<trajectory_msgs::JointTrajectory>(
384 nh_,
"joint_trajectory",
385 pnh_,
"trajectory_out", 1,
true);
387 nh_,
"trajectory_in",
399 pnh_.
param(
"replan_interval", interval, 0.2);
403 int queue_size_limit;
404 nh_group.
param(
"queue_size_limit", queue_size_limit, 0);
407 status_.status = planner_cspace_msgs::PlannerStatus::DONE;
413 nh_group.
param(
"link0_name",
links_[0].name_, std::string(
"link0"));
414 nh_group.
param(
"link0_joint_radius",
links_[0].radius_[0], 0.07
f);
415 nh_group.
param(
"link0_end_radius",
links_[0].radius_[1], 0.07
f);
416 nh_group.
param(
"link0_length",
links_[0].length_, 0.135
f);
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);
422 nh_group.
param(
"link1_name",
links_[1].name_, std::string(
"link1"));
423 nh_group.
param(
"link1_joint_radius",
links_[1].radius_[0], 0.07
f);
424 nh_group.
param(
"link1_end_radius",
links_[1].radius_[1], 0.07
f);
425 nh_group.
param(
"link1_length",
links_[1].length_, 0.27
f);
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);
442 nh_group.
param(
"link0_coef", euclid_cost_coef[0], 1.0
f);
443 nh_group.
param(
"link1_coef", euclid_cost_coef[1], 1.5
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");
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)
495 int dist = std::max(std::abs(
d[0]), abs(
d[1]));
496 int c = std::floor(100.0 * (range - dist) / range);
505 nh_group.
param(
"range", range, 8);
515 nh_group.
param(
"num_threads", num_threads, 1);
516 omp_set_num_threads(num_threads);
521 const int t0,
const int t1,
522 float& gt0,
float& gt1)
529 const float gt0,
const float gt1)
551 ROS_INFO(
"Planning from (%d, %d) to (%d, %d)",
552 s[0],
s[1], e[0], e[1]);
556 ROS_WARN(
"Path plan failed (current status is in collision)");
557 status_.error = planner_cspace_msgs::PlannerStatus::PATH_NOT_FOUND;
562 ROS_WARN(
"Path plan failed (goal status is in collision)");
563 status_.error = planner_cspace_msgs::PlannerStatus::PATH_NOT_FOUND;
569 std::vector<Astar::VecWithCost> starts;
570 starts.emplace_back(
s);
582 std::list<Astar::Vec> path_grid;
584 float cancel = std::numeric_limits<float>::max();
588 starts, e, path_grid,
model_,
592 ROS_WARN(
"Path plan failed (goal unreachable)");
593 status_.error = planner_cspace_msgs::PlannerStatus::PATH_NOT_FOUND;
604 for (
auto& n : path_grid)
612 ROS_INFO(
" next: %d, %d", n[0], n[1]);
623 float prec = 2.0 * M_PI /
static_cast<float>(
resolution_);
626 egp[0] += std::ceil(-egp[0] / M_PI * 2.0) * M_PI * 2.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;
640 for (
auto& g : path_grid)
646 printf(
"\033[31ms\033[0m");
648 printf(
"\033[31me\033[0m");
650 printf(
"\033[34m*\033[0m");
652 printf(
"%d",
cm_[p] / 11);
669 int main(
int argc,
char* argv[])
671 ros::init(argc, argv,
"planner_2dof_serial_joints");
674 std::vector<planner_cspace::planner_2dof_serial_joints::Planner2dofSerialJointsNode::Ptr> jys;
676 pnh.
param(
"num_groups", n, 1);
677 for (
int i = 0; i < n; i++)
680 pnh.
param(
"group" + std::to_string(i) +
"_name",
681 name, std::string(
"group") + std::to_string(i));