22#include <angles/angles.h>
23#include <geometry_msgs/msg/pose_stamped.hpp>
24#include <geometry_msgs/msg/twist.hpp>
25#include <rclcpp/rclcpp.hpp>
26#include <visualization_msgs/msg/marker_array.hpp>
29#include <boost/intrusive_ptr.hpp>
30#include <nav_2d_utils/tf_help.hpp>
31#include <pluginlib/class_list_macros.hpp>
33using namespace std::chrono_literals;
36namespace forward_local_planner
49 RCLCPP_DEBUG_STREAM(
nh_->get_logger(),
"activating controller ForwardLocalPlanner");
70 const rclcpp_lifecycle::LifecycleNode::WeakPtr & node, std::string name,
71 const std::shared_ptr<tf2_ros::Buffer> & tf,
72 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> & costmap_ros)
108 "[ForwardLocalPlanner] max linear speed: %lf, max angular speed: %lf, k_rho: %lf, "
113 "forward_local_planner/carrot_goal_marker", 1);
131 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[ForwardLocalPlanner.k_rho: " <<
k_rho_);
132 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[ForwardLocalPlanner.k_alpha: " <<
k_alpha_);
133 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[ForwardLocalPlanner.k_betta: " <<
k_betta_);
149 const Eigen::Vector3f & pos,
const Eigen::Vector3f & vel,
float maxdist,
float maxanglediff,
150 float maxtime,
float dt, std::vector<Eigen::Vector3f> & outtraj)
155 Eigen::Vector3f currentpos = pos;
173 auto dx = newpos[0] - currentpos[0];
174 auto dy = newpos[1] - currentpos[1];
175 float dist, angledist;
178 dist = sqrt(dx * dx + dy * dy);
187 angledist = fabs(angles::shortest_angular_distance(currentpos[2], newpos[2]));
188 if (angledist > maxanglediff)
195 outtraj.push_back(newpos);
214 const Eigen::Vector3f & pos,
const Eigen::Vector3f & vel,
double dt)
216 Eigen::Vector3f new_pos = Eigen::Vector3f::Zero();
217 new_pos[0] = pos[0] + (vel[0] * cos(pos[2]) + vel[1] * cos(M_PI_2 + pos[2])) * dt;
218 new_pos[1] = pos[1] + (vel[0] * sin(pos[2]) + vel[1] * sin(M_PI_2 + pos[2])) * dt;
219 new_pos[2] = pos[2] + vel[2] * dt;
230 visualization_msgs::msg::Marker marker;
232 marker.header.frame_id =
costmapRos_->getGlobalFrameID();
233 marker.header.stamp =
nh_->now();
234 marker.ns =
"my_namespace2";
236 marker.type = visualization_msgs::msg::Marker::ARROW;
237 marker.action = visualization_msgs::msg::Marker::ADD;
238 marker.pose.orientation.w = 1;
239 marker.lifetime = rclcpp::Duration(1.0s);
241 marker.scale.x = 0.1;
242 marker.scale.y = 0.3;
243 marker.scale.z = 0.1;
244 marker.color.a = 1.0;
247 marker.color.b = 1.0;
249 geometry_msgs::msg::Point start, end;
253 end.x = x + 0.5 * cos(phi);
254 end.y = y + 0.5 * sin(phi);
256 marker.points.push_back(start);
257 marker.points.push_back(end);
259 visualization_msgs::msg::MarkerArray ma;
260 ma.markers.push_back(marker);
267 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[ForwardLocalPlanner] cleaning markers.");
268 visualization_msgs::msg::Marker marker;
270 marker.header.frame_id =
costmapRos_->getGlobalFrameID();
271 marker.header.stamp =
nh_->now();
272 marker.ns =
"my_namespace2";
274 marker.action = visualization_msgs::msg::Marker::DELETEALL;
276 visualization_msgs::msg::MarkerArray ma;
277 ma.markers.push_back(marker);
283 rclcpp::Node::SharedPtr nh_, geometry_msgs::msg::Twist & cmd_vel,
double max_linear_x_speed_,
284 double max_angular_z_speed_)
286 if (max_angular_z_speed_ == 0 || max_linear_x_speed_ == 0)
return;
288 if (cmd_vel.angular.z == 0)
290 cmd_vel.linear.x = max_linear_x_speed_;
294 double kurvature = cmd_vel.linear.x / cmd_vel.angular.z;
296 double linearAuthority = fabs(cmd_vel.linear.x / max_linear_x_speed_);
297 double angularAuthority = fabs(cmd_vel.angular.z / max_angular_z_speed_);
298 if (linearAuthority < angularAuthority)
301 cmd_vel.linear.x = max_linear_x_speed_;
302 cmd_vel.angular.z = kurvature / max_linear_x_speed_;
304 nh_->get_logger(),
"k=" << kurvature <<
"lets go to maximum linear capacity: " << cmd_vel);
309 cmd_vel.angular.x = max_angular_z_speed_;
310 cmd_vel.linear.x = kurvature * max_angular_z_speed_;
311 RCLCPP_WARN_STREAM(nh_->get_logger(),
"lets go to maximum angular capacity: " << cmd_vel);
323 const geometry_msgs::msg::PoseStamped & currentPose,
324 const geometry_msgs::msg::Twist & , nav2_core::GoalChecker * goal_checker)
328 if (this->
plan_.size() > 0)
331 nh_->get_logger(),
"[ForwardLocalPlanner] Current pose frame id: "
332 <<
plan_.front().header.frame_id
333 <<
", path pose frame id: " << currentPose.header.frame_id);
335 if (
plan_.front().header.frame_id != currentPose.header.frame_id)
337 RCLCPP_ERROR_STREAM(
nh_->get_logger(),
"[ForwardLocalPlanner] Inconsistent frames");
345 geometry_msgs::msg::Pose posetol;
346 geometry_msgs::msg::Twist twistol;
347 if (goal_checker->getTolerances(posetol, twistol))
355 <<
", yaw_goal_tolerance_: "
361 nh_->get_logger(),
"[ForwardLocalPlanner] could not get tolerances from goal checker");
365 geometry_msgs::msg::TwistStamped cmd_vel;
368 nh_->get_logger(),
"[ForwardLocalPlanner] ----- COMPUTE VELOCITY COMMAND LOCAL PLANNER ---");
377 const geometry_msgs::msg::Point & p = pose.pose.position;
379 tf2::fromMsg(pose.pose.orientation, q);
382 double dx = p.x - currentPose.pose.position.x;
383 double dy = p.y - currentPose.pose.position.y;
384 double dist = sqrt(dx * dx + dy * dy);
386 double pangle = tf2::getYaw(q);
387 double angle = tf2::getYaw(currentPose.pose.orientation);
388 double angular_error = angles::shortest_angular_distance(pangle, angle);
396 "current index: %d, carrot goal percentaje: %lf, dist: %lf, maxdist: %lf, angle_error: "
408 nh_->get_logger(),
"[ForwardLocalPlanner] selected carrot pose index "
414 cmd_vel.twist.linear.x = 0;
415 cmd_vel.twist.angular.z = 0;
425 const geometry_msgs::msg::PoseStamped & finalgoalpose =
plan_.back();
427 const geometry_msgs::msg::Point & goalposition = carrot_goalpose.pose.position;
429 tf2::Quaternion carrotGoalQ;
430 tf2::fromMsg(carrot_goalpose.pose.orientation, carrotGoalQ);
434 double betta = tf2::getYaw(carrot_goalpose.pose.orientation) +
betta_offset_;
435 double dx = goalposition.x - currentPose.pose.position.x;
436 double dy = goalposition.y - currentPose.pose.position.y;
439 double rho_error = sqrt(dx * dx + dy * dy);
441 tf2::Quaternion currentOrientation;
442 tf2::convert(currentPose.pose.orientation, currentOrientation);
445 double theta = tf2::getYaw(currentOrientation);
446 double alpha = atan2(dy, dx);
449 double alpha_error = angles::shortest_angular_distance(alpha, theta);
450 double betta_error = angles::shortest_angular_distance(betta, theta);
460 vetta =
k_rho_ * rho_error;
470 RCLCPP_DEBUG(
nh_->get_logger(),
"GOAL REACHED");
496 cmd_vel.twist.linear.x = vetta;
497 cmd_vel.twist.angular.z = gamma;
506 nh_->get_logger(),
"Forward local planner,"
508 <<
" theta: " << theta << std::endl
509 <<
" betta: " << betta << std::endl
510 <<
" err_x: " << dx << std::endl
511 <<
" err_y:" << dy << std::endl
512 <<
" rho_error:" << rho_error << std::endl
513 <<
" alpha_error:" << alpha_error << std::endl
514 <<
" betta_error:" << betta_error << std::endl
515 <<
" vetta:" << vetta << std::endl
516 <<
" gamma:" << gamma << std::endl
526 assert(currentPose.header.frame_id ==
"odom" || currentPose.header.frame_id ==
"map");
527 auto global_pose = currentPose;
531 auto yaw = tf2::getYaw(global_pose.pose.orientation);
533 auto & pos = global_pose.pose.position;
535 Eigen::Vector3f currentpose(pos.x, pos.y, yaw);
536 Eigen::Vector3f currentvel(
537 cmd_vel.twist.linear.x, cmd_vel.twist.linear.y, cmd_vel.twist.angular.z);
539 std::vector<Eigen::Vector3f> trajectory;
541 currentpose, currentvel, 0.8 , M_PI / 8 , 3.0 , 0.05 ,
545 bool aceptedplan =
true;
551 for (
auto & p : trajectory)
553 float dx = p[0] - finalgoalpose.pose.position.x;
554 float dy = p[1] - finalgoalpose.pose.position.y;
556 float dst = sqrt(dx * dx + dy * dy);
563 costmap2d->worldToMap(p[0], p[1], mx, my);
573 if (costmap2d->getCost(mx, my) >= nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
582 bool success =
false;
587 RCLCPP_DEBUG(
nh_->get_logger(),
"simulated trajectory is accepted.");
591 RCLCPP_DEBUG(
nh_->get_logger(),
"simulated trajectory is not accepted. Stop command.");
594 cmd_vel.twist.linear.x = 0;
595 cmd_vel.twist.angular.z = 0;
599 RCLCPP_DEBUG(
nh_->get_logger(),
"Start waiting obstacle disappear");
607 nh_->get_logger(),
"waiting obstacle disappear, elapsed: %lf seconds",
608 waitingduration.seconds());
613 nh_->get_logger(),
"TIMEOUT waiting obstacle disappear, elapsed: %lf seconds",
614 waitingduration.seconds());
624 "[ForwardLocalPlanner] object detected waiting stopped until it disappears.");
627 cmd_vel.header.stamp =
nh_->now();
635 "ForwardLocalPlanner::setSpeedLimit invoked. Ignored, funcionality not "
653 nav_msgs::msg::Path transformedPlan;
657 for (
auto & p : plan.poses)
659 geometry_msgs::msg::PoseStamped transformedPose;
660 nav_2d_utils::transformPose(
tf_,
costmapRos_->getGlobalFrameID(), p, transformedPose, ttol);
661 transformedPose.header.frame_id =
costmapRos_->getGlobalFrameID();
662 transformedPlan.poses.push_back(transformedPose);
665 plan_ = transformedPlan.poses;
std::vector< geometry_msgs::msg::PoseStamped > plan_
double max_linear_x_speed_
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmapRos_
Eigen::Vector3f computeNewPositions(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, double dt)
double transform_tolerance_
std::shared_ptr< tf2_ros::Buffer > tf_
virtual ~ForwardLocalPlanner()
rclcpp::Duration waitingTimeout_
double xy_goal_tolerance_
void generateTrajectory(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, float maxdist, float maxangle, float maxtime, float dt, std::vector< Eigen::Vector3f > &outtraj)
virtual void setSpeedLimit(const double &speed_limit, const bool &percentage) override
nav2_util::LifecycleNode::SharedPtr nh_
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, const std::shared_ptr< tf2_ros::Buffer > &tf, const std::shared_ptr< nav2_costmap_2d::Costmap2DROS > &costmap_ros) override
rclcpp::Time waitingStamp_
const double alpha_offset_
double max_angular_z_speed_
void publishGoalMarker(double x, double y, double phi)
const double betta_offset_
virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity, nav2_core::GoalChecker *goal_checker) override
nav2_core computeVelocityCommands - calculates the best command given the current pose and velocity
double yaw_goal_tolerance_
void setPlan(const nav_msgs::msg::Path &path) override
nav2_core setPlan - Sets the global plan
void deactivate() override
rclcpp_lifecycle::LifecyclePublisher< visualization_msgs::msg::MarkerArray >::SharedPtr goalMarkerPublisher_
void declareOrSet(rclcpp_lifecycle::LifecycleNode::SharedPtr &node, std::string param, T &value)
void clamp(rclcpp::Node::SharedPtr nh_, geometry_msgs::msg::Twist &cmd_vel, double max_linear_x_speed_, double max_angular_z_speed_)