21#include <angles/angles.h>
25#include <boost/intrusive_ptr.hpp>
27#include <nav_2d_utils/tf_help.hpp>
28#include <pluginlib/class_list_macros.hpp>
29#include <visualization_msgs/msg/marker_array.hpp>
32PLUGINLIB_EXPORT_CLASS(
35using namespace std::literals::chrono_literals;
39namespace backward_local_planner
57 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"activating controller BackwardLocalPlanner");
68 RCLCPP_WARN_STREAM(
nh_->get_logger(),
"[BackwardLocalPlanner] deactivated");
76 RCLCPP_WARN_STREAM(
nh_->get_logger(),
"[BackwardLocalPlanner] cleanup");
88void tryGetOrSet(rclcpp_lifecycle::LifecycleNode::SharedPtr & node, std::string param,
T & value)
90 if (!node->get_parameter(param, value))
92 node->set_parameter(rclcpp::Parameter(param, value));
97 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name,
98 const std::shared_ptr<tf2_ros::Buffer> & tf,
99 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> & costmap_ros)
103 this->
nh_ = parent.lock();
145 nh_->get_logger(),
"[BackwardLocalPlanner] carrot_angular_distance ("
155 nh_->get_logger(),
"[BackwardLocalPlanner] carrot_linear_distance ("
163 "backward_local_planner/goal_marker", 1);
165 planPub_ =
nh_->create_publisher<nav_msgs::msg::Path>(
"backward_local_planner/path", 1);
170 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"--- parameters ---");
172 RCLCPP_INFO_STREAM(
nh_->get_logger(),
name_ +
".k_rho:" <<
k_rho_);
206 nh_->get_logger(),
"[BackwardLocalPlanner] carrot_angular_distance ("
220 nh_->get_logger(),
"[BackwardLocalPlanner] carrot_linear_distance ("
228 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"--- end params ---");
232 const double & ,
const bool & )
236 "BackwardLocalPlanner::setSpeedLimit invoked. Ignored, funcionality not "
245 const geometry_msgs::msg::PoseStamped & tfpose,
double & dist,
double & angular_error)
247 double angle = tf2::getYaw(tfpose.pose.orientation);
249 const geometry_msgs::msg::Point & carrot_point = carrot_pose.pose.position;
251 tf2::Quaternion carrot_orientation;
252 tf2::convert(carrot_pose.pose.orientation, carrot_orientation);
253 geometry_msgs::msg::Pose currentPoseDebugMsg = tfpose.pose;
256 double dx = carrot_point.x - tfpose.pose.position.x;
257 double dy = carrot_point.y - tfpose.pose.position.y;
259 dist = sqrt(dx * dx + dy * dy);
261 double pangle = tf2::getYaw(carrot_orientation);
262 angular_error = fabs(angles::shortest_angular_distance(pangle, angle));
265 nh_->get_logger(),
"[BackwardLocalPlanner] Compute carrot errors from current pose. (linear "
266 << dist <<
")(angular " << angular_error <<
")" << std::endl
267 <<
"Current carrot pose: " << std::endl
268 << carrot_pose << std::endl
269 <<
"Current actual pose:" << std::endl
270 << currentPoseDebugMsg);
280 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[BackwardsLocalPlanner] --- Carrot update ---");
281 double disterr = 0, angleerr = 0;
290 nh_->get_logger(),
"[BackwardsLocalPlanner] update carrot goal: Current index: "
294 "[BackwardsLocalPlanner] update carrot goal: linear error %lf, angular error: %lf", disterr,
303 nh_->get_logger(),
"[BackwardsLocalPlanner] move carrot fw "
322 nh_->get_logger(),
"[BackwardsLocalPlanner] Current index carrot goal: %d",
326 "[BackwardsLocalPlanner] Update carrot goal: linear error %lf (xytol: %lf), angular error: "
332 nh_->get_logger(),
"[BackwardsLocalPlanner] carrot in goal radius: %d",
333 carrotInGoalLinearRange);
335 RCLCPP_INFO(
nh_->get_logger(),
"[BackwardsLocalPlanner] ---End carrot update---");
337 return carrotInGoalLinearRange;
349 double disterr = 0, angleerr = 0;
353 nh_->get_logger(),
"[BackwardLocalPlanner] Divergence check. carrot goal distance. was: "
355 <<
", now it is: " << disterr);
361 const double MARGIN_FACTOR = 1.2;
366 "[BackwardLocalPlanner] Divergence detected. The same carrot goal distance was previously: "
385 const geometry_msgs::msg::PoseStamped & tfpose)
394 const geometry_msgs::msg::Point & carrot_point = carrot_pose.pose.position;
395 double yaw = tf2::getYaw(carrot_pose.pose.orientation);
398 double vx = cos(yaw);
399 double vy = sin(yaw);
403 double c = -vx * carrot_point.x - vy * carrot_point.y;
404 const double C_OFFSET_METERS = 0.05;
405 double check = vx * tfpose.pose.position.x + vy * tfpose.pose.position.y + c + C_OFFSET_METERS;
409 "[BackwardLocalPlanner] half plane constraint:" << vx <<
"*" << carrot_point.x <<
" + " << vy
410 <<
"*" << carrot_point.y <<
" + " << c);
412 nh_->get_logger(),
"[BackwardLocalPlanner] constraint evaluation: "
413 << vx <<
"*" << tfpose.pose.position.x <<
" + " << vy <<
"*"
414 << tfpose.pose.position.y <<
" + " << c <<
" = " << check);
420 const geometry_msgs::msg::PoseStamped & tfpose,
421 const geometry_msgs::msg::Twist & ,
double angle_error,
bool & linearGoalReached,
422 nav2_core::GoalChecker * )
425 double gdx = finalgoal.pose.position.x - tfpose.pose.position.x;
426 double gdy = finalgoal.pose.position.y - tfpose.pose.position.y;
427 double goaldist = sqrt(gdx * gdx + gdy * gdy);
429 auto abs_angle_error = fabs(angle_error);
432 nh_->get_logger(),
"[BackwardLocalPlanner] goal check. linear dist: "
433 << goaldist <<
"(" << this->xy_goal_tolerance_ <<
")"
434 <<
", angular dist: " << abs_angle_error <<
"("
435 << this->yaw_goal_tolerance_ <<
")");
449 const geometry_msgs::msg::PoseStamped & ,
double & vetta,
double & gamma,
450 double alpha_error,
double betta_error,
double rho_error)
454 vetta =
k_rho_ * rho_error;
470 const geometry_msgs::msg::PoseStamped & pose,
const geometry_msgs::msg::Twist & velocity,
471 nav2_core::GoalChecker * goal_checker)
475 "[BackwardLocalPlanner] ------------------- LOCAL PLANNER LOOP -----------------");
482 nh_->get_logger(),
"[BackwardLocalPlanner] Current pose frame id: "
484 <<
", path pose frame id: " << pose.header.frame_id);
488 RCLCPP_ERROR_STREAM(
nh_->get_logger(),
"[BackwardLocalPlanner] Inconsistent frames");
496 geometry_msgs::msg::Pose posetol;
497 geometry_msgs::msg::Twist twistol;
498 if (goal_checker->getTolerances(posetol, twistol))
505 nh_->get_logger(),
"[BackwardLocalPlanner] xy_goal_tolerance_: "
512 nh_->get_logger(),
"[BackwardLocalPlanner] could not get tolerances from goal checker");
518 "[BackwardLocalPlanner] ------------------- LOCAL PLANNER LOOP -----------------");
520 geometry_msgs::msg::TwistStamped cmd_vel;
521 RCLCPP_INFO(
nh_->get_logger(),
"[BackwardLocalPlanner] LOCAL PLANNER LOOP");
522 geometry_msgs::msg::PoseStamped paux;
523 geometry_msgs::msg::PoseStamped tfpose;
529 "[BackwardLocalPlanner] missing robot pose, canceling compute Velocity Command");
531 bool divergenceDetected =
false;
533 bool emergency_stop =
false;
534 if (divergenceDetected)
537 nh_->get_logger(),
"[BackwardLocalPlanner] Divergence detected. Sending emergency stop.");
538 emergency_stop =
true;
542 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[BackwardLocalPlanner] carrot goal created");
546 cmd_vel.twist.linear.x = 0;
547 cmd_vel.twist.angular.z = 0;
549 nh_->get_logger(),
"[BackwardLocalPlanner] emergency stop, exit compute commands");
555 double rho_error, betta_error, alpha_error;
559 tf2::convert(tfpose.pose.orientation, q);
564 const geometry_msgs::msg::PoseStamped & carrotgoalpose =
567 nh_->get_logger(),
"[BackwardLocalPlanner] carrot goal pose current index: "
570 const geometry_msgs::msg::Point & carrotGoalPosition = carrotgoalpose.pose.position;
572 tf2::Quaternion goalQ;
573 tf2::fromMsg(carrotgoalpose.pose.orientation, goalQ);
574 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[BackwardLocalPlanner] -- Control Policy --");
576 double betta = tf2::getYaw(goalQ);
577 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[BackwardLocalPlanner] goal orientation: " << betta);
580 double dx = carrotGoalPosition.x - tfpose.pose.position.x;
581 double dy = carrotGoalPosition.y - tfpose.pose.position.y;
584 rho_error = sqrt(dx * dx + dy * dy);
587 double theta = tf2::getYaw(q);
588 double alpha = atan2(dy, dx);
591 alpha_error = angles::shortest_angular_distance(alpha, theta);
592 betta_error = angles::shortest_angular_distance(betta, theta);
595 bool linearGoalReached;
596 bool currentPoseInGoal =
603 if (currentPoseInGoal && carrotInFinalGoalIndex)
609 "[BackwardLocalPlanner] GOAL REACHED. Send stop command and skipping trajectory collision: "
611 cmd_vel.twist.linear.x = 0;
612 cmd_vel.twist.angular.z = 0;
616 carrotInLinearGoalRange &&
631 tfpose, vetta, gamma, alpha_error, betta_error, rho_error);
636 vetta =
k_rho_ * rho_error;
645 "[BackwardLocalPlanner] we entered in a pure spinning state even in not pure-spining "
647 "carrotDistanceGoalReached: %d",
648 carrotInLinearGoalRange);
657 cmd_vel.twist.linear.x = vetta;
658 cmd_vel.twist.angular.z = gamma;
681 nh_->get_logger(),
"[BackwardLocalPlanner] local planner,"
683 <<
" current pose in goal: " << currentPoseInGoal << std::endl
684 <<
" carrot in final goal index: " << carrotInFinalGoalIndex << std::endl
685 <<
" carrot in linear goal range: " << carrotInLinearGoalRange << std::endl
689 <<
" theta: " << theta << std::endl
690 <<
" betta: " << theta << std::endl
691 <<
" err_x: " << dx << std::endl
692 <<
" err_y:" << dy << std::endl
693 <<
" rho_error:" << rho_error << std::endl
694 <<
" alpha_error:" << alpha_error << std::endl
695 <<
" betta_error:" << betta_error << std::endl
696 <<
" vetta:" << vetta << std::endl
697 <<
" gamma:" << gamma << std::endl
698 <<
" cmd_vel.lin.x:" << cmd_vel.twist.linear.x << std::endl
699 <<
" cmd_vel.ang.z:" << cmd_vel.twist.angular.z);
705 if (carrotHalfPlaneConstraintFailure)
709 "[BackwardLocalPlanner] CarrotHalfPlaneConstraintFailure detected. Sending "
710 "emergency stop and success to the planner.");
711 cmd_vel.twist.linear.x = 0;
719 geometry_msgs::msg::PoseStamped global_pose;
723 auto yaw = tf2::getYaw(global_pose.pose.orientation);
725 auto & pos = global_pose.pose.position;
727 Eigen::Vector3f currentpose(pos.x, pos.y, yaw);
728 Eigen::Vector3f currentvel(
729 cmd_vel.twist.linear.x, cmd_vel.twist.linear.y, cmd_vel.twist.angular.z);
730 std::vector<Eigen::Vector3f> trajectory;
732 currentpose, currentvel, 0.8 , M_PI / 8 , 3.0 , 0.05 ,
736 bool acceptedLocalTrajectoryFreeOfObstacles =
true;
748 geometry_msgs::msg::Twist mockzerospeed;
750 for (
auto & p : trajectory)
762 float dx = p[0] - finalgoalpose.pose.position.x;
763 float dy = p[1] - finalgoalpose.pose.position.y;
765 float dst = sqrt(dx * dx + dy * dy);
770 "[BackwardLocalPlanner] trajectory simulation for collision checking: goal "
771 "reached with no collision");
775 costmap2d->worldToMap(p[0], p[1], mx, my);
786 if (costmap2d->getCost(mx, my) >= nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
788 acceptedLocalTrajectoryFreeOfObstacles =
false;
791 "[BackwardLocalPlanner] ABORTED LOCAL PLAN BECAUSE OBSTACLE DETEDTED at point "
792 << i <<
"/" << trajectory.size() << std::endl
793 << p[0] <<
", " << p[1]);
802 nh_->get_logger(),
"[BackwardLocalPlanner] Abort local - Backwards global plan size: %ld",
804 cmd_vel.twist.angular.z = 0;
805 cmd_vel.twist.linear.x = 0;
810 if (acceptedLocalTrajectoryFreeOfObstacles)
815 "[BackwardLocalPlanner] accepted local trajectory free of obstacle. Local planner "
823 cmd_vel.twist.linear.x = 0;
824 cmd_vel.twist.angular.z = 0;
831 nh_->get_logger(),
"[BackwardLocalPlanner][Not accepted local plan] starting countdown");
840 nh_->get_logger(),
"[BackwardLocalPlanner][Abort local] timeout! duration %lf/%f",
843 cmd_vel.twist.linear.x = 0;
844 cmd_vel.twist.angular.z = 0;
860 RCLCPP_INFO(
nh_->get_logger(),
"[BackwardLocalPlanner] isGoalReached call");
866 double lineardisterr, angleerr;
867 bool inCarrotRange =
false;
881 "[BackwardLocalPlanner] Finding initial carrot goal i=%d - error to carrot, linear = %lf "
883 "angular : %lf (%lf)",
891 "[BackwardLocalPlanner] Finding initial carrot goal i=%d - in carrot Range",
893 inCarrotRange =
true;
911 "[BackwardLocalPlanner] Finding initial carrot goal i=%d - carrot out of range, searching "
922 nh_->get_logger(),
"[BackwardLocalPlanner] setPlan: (found first carrot:"
923 << inCarrotRange <<
") initial carrot point index: "
926 return inCarrotRange;
934 RCLCPP_INFO(
nh_->get_logger(),
"[BackwardLocalPlanner] resample precise");
939 "[BackwardLocalPlanner] resample precise skipping, size: " <<
backwardsPlanPath_.size());
949 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[BackwardLocalPlanner] resample precise, check: " << i);
953 tf2::Quaternion qCurrent, qNext;
954 tf2::convert(currpose.pose.orientation, qCurrent);
955 tf2::convert(nextpose.pose.orientation, qNext);
957 double dx = nextpose.pose.position.x - currpose.pose.position.x;
958 double dy = nextpose.pose.position.y - currpose.pose.position.y;
959 double dist = sqrt(dx * dx + dy * dy);
961 bool resample =
false;
962 if (dist > maxallowedLinearError)
965 nh_->get_logger(),
"[BackwardLocalPlanner] resampling point, linear distance:"
966 << dist <<
"(" << maxallowedLinearError <<
")" << i);
971 double currentAngle = tf2::getYaw(qCurrent);
972 double nextAngle = tf2::getYaw(qNext);
974 double angularError = fabs(angles::shortest_angular_distance(currentAngle, nextAngle));
975 if (angularError > maxallowedAngularError)
979 nh_->get_logger(),
"[BackwardLocalPlanner] resampling point, angular distance:"
980 << angularError <<
"(" << maxallowedAngularError <<
")" << i);
986 geometry_msgs::msg::PoseStamped pintermediate;
987 auto duration = rclcpp::Time(nextpose.header.stamp) - rclcpp::Time(currpose.header.stamp);
989 pintermediate.header.frame_id = currpose.header.frame_id;
990 pintermediate.header.stamp = rclcpp::Time(currpose.header.stamp) + duration * 0.5;
992 pintermediate.pose.position.x = 0.5 * (currpose.pose.position.x + nextpose.pose.position.x);
993 pintermediate.pose.position.y = 0.5 * (currpose.pose.position.y + nextpose.pose.position.y);
994 pintermediate.pose.position.z = 0.5 * (currpose.pose.position.z + nextpose.pose.position.z);
995 tf2::Quaternion intermediateQuat = tf2::slerp(qCurrent, qNext, 0.5);
996 pintermediate.pose.orientation = tf2::toMsg(intermediateQuat);
1007 nh_->get_logger(),
"[BackwardLocalPlanner] End resampling. resampled:" << counter
1008 <<
" new inserted poses "
1023 "[BackwardLocalPlanner] setPlan: new global plan received ( " << path.poses.size() <<
")");
1026 nav_msgs::msg::Path transformedPlan;
1029 for (
auto & p : path.poses)
1031 geometry_msgs::msg::PoseStamped transformedPose;
1032 nav_2d_utils::transformPose(
tf_,
costmapRos_->getGlobalFrameID(), p, transformedPose, ttol);
1033 transformedPose.header.frame_id =
costmapRos_->getGlobalFrameID();
1034 transformedPlan.poses.push_back(transformedPose);
1040 geometry_msgs::msg::PoseStamped tfpose;
1043 RCLCPP_ERROR(
nh_->get_logger(),
"Failure getting pose from Backward local planner");
1047 geometry_msgs::msg::PoseStamped posestamped = tfpose;
1051 nav_msgs::msg::Path planMsg;
1053 planMsg.header.frame_id =
costmapRos_->getGlobalFrameID();
1054 planMsg.header.stamp =
nh_->now();
1063 if (path.poses.size() == 0)
1065 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[BackwardLocalPlanner] received plan without any pose");
1072 if (!foundInitialCarrotGoal)
1076 "[BackwardLocalPlanner] new plan rejected. The initial point in the global path is "
1077 "too much far away from the current state (according to carrot_distance "
1092 const Eigen::Vector3f & pos,
const Eigen::Vector3f & vel,
float maxdist,
float maxanglediff,
1093 float maxtime,
float dt, std::vector<Eigen::Vector3f> & outtraj)
1098 Eigen::Vector3f currentpos = pos;
1112 auto loop_vel = vel;
1116 auto dx = newpos[0] - currentpos[0];
1117 auto dy = newpos[1] - currentpos[1];
1118 float dist, angledist;
1121 dist = sqrt(dx * dx + dy * dy);
1130 angledist = angles::shortest_angular_distance(currentpos[2], newpos[2]);
1131 if (angledist > maxanglediff)
1138 outtraj.push_back(newpos);
1151 currentpos = newpos;
1157 const Eigen::Vector3f & pos,
const Eigen::Vector3f & vel,
double dt)
1159 Eigen::Vector3f new_pos = Eigen::Vector3f::Zero();
1160 new_pos[0] = pos[0] + (vel[0] * cos(pos[2]) + vel[1] * cos(M_PI_2 + pos[2])) * dt;
1161 new_pos[1] = pos[1] + (vel[0] * sin(pos[2]) + vel[1] * sin(M_PI_2 + pos[2])) * dt;
1162 new_pos[2] = pos[2] + vel[2] * dt;
1168 visualization_msgs::msg::Marker marker;
1169 marker.header.frame_id = this->
costmapRos_->getGlobalFrameID();
1170 marker.header.stamp =
nh_->now();
1172 marker.ns =
"my_namespace2";
1174 marker.type = visualization_msgs::msg::Marker::ARROW;
1175 marker.action = visualization_msgs::msg::Marker::DELETEALL;
1177 visualization_msgs::msg::MarkerArray ma;
1178 ma.markers.push_back(marker);
1190 visualization_msgs::msg::Marker marker;
1191 marker.header.frame_id = this->
costmapRos_->getGlobalFrameID();
1192 marker.header.stamp =
nh_->now();
1194 marker.ns =
"my_namespace2";
1196 marker.type = visualization_msgs::msg::Marker::ARROW;
1197 marker.action = visualization_msgs::msg::Marker::ADD;
1198 marker.lifetime = rclcpp::Duration(1.0
s);
1200 marker.pose.orientation.w = 1;
1202 marker.scale.x = 0.05;
1203 marker.scale.y = 0.15;
1204 marker.scale.z = 0.05;
1205 marker.color.a = 1.0;
1212 geometry_msgs::msg::Point start, end;
1216 end.x = x + 0.5 * cos(phi);
1217 end.y = y + 0.5 * sin(phi);
1219 marker.points.push_back(start);
1220 marker.points.push_back(end);
1222 visualization_msgs::msg::MarkerArray ma;
1223 ma.markers.push_back(marker);
bool updateCarrotGoal(const geometry_msgs::msg::PoseStamped &pose)
rad carrot_angular_distance_
bool checkCarrotHalfPlainConstraint(const geometry_msgs::msg::PoseStamped &pose)
Eigen::Vector3f computeNewPositions(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, double dt)
meter divergenceDetectionLastCarrotLinearDistance_
void publishGoalMarker(double x, double y, double phi)
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
void deactivate() override
const double betta_offset_
std::shared_ptr< tf2_ros::Buffer > tf_
rclcpp::Duration waitingTimeout_
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_
const double alpha_offset_
void straightBackwardsAndPureSpinCmd(const geometry_msgs::msg::PoseStamped &pose, double &vetta, double &gamma, double alpha_error, double betta_error, double rho_error)
std::vector< geometry_msgs::msg::PoseStamped > backwardsPlanPath_
void generateTrajectory(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, float maxdist, float maxangle, float maxtime, float dt, std::vector< Eigen::Vector3f > &outtraj)
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< visualization_msgs::msg::MarkerArray > > goalMarkerPublisher_
bool findInitialCarrotGoal(geometry_msgs::msg::PoseStamped &pose)
bool divergenceDetectionUpdate(const geometry_msgs::msg::PoseStamped &pose)
virtual ~BackwardLocalPlanner()
void setPlan(const nav_msgs::msg::Path &path) override
nav2_core setPlan - Sets the global plan
double xy_goal_tolerance_
bool inGoalPureSpinningState_
double max_linear_x_speed_
void computeCurrentEuclideanAndAngularErrorsToCarrotGoal(const geometry_msgs::msg::PoseStamped &pose, double &dist, double &angular_error)
bool enable_obstacle_checking_
double linear_mode_rho_error_threshold_
bool checkCurrentPoseInGoalRange(const geometry_msgs::msg::PoseStamped &tfpose, const geometry_msgs::msg::Twist ¤tTwist, double angle_error, bool &linearGoalReached, nav2_core::GoalChecker *goalChecker)
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< nav_msgs::msg::Path > > planPub_
bool straightBackwardsAndPureSpinningMode_
virtual void setSpeedLimit(const double &speed_limit, const bool &percentage) override
double max_angular_z_speed_
double transform_tolerance_
rclcpp::Time waitingStamp_
bool resamplePrecisePlan()
int currentCarrotPoseIndex_
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmapRos_
rclcpp_lifecycle::LifecycleNode::SharedPtr nh_
bool resetDivergenceDetection()
void declareOrSet(rclcpp_lifecycle::LifecycleNode::SharedPtr &node, std::string param, T &value)
void tryGetOrSet(rclcpp_lifecycle::LifecycleNode::SharedPtr &node, std::string param, T &value)