28#include <rclcpp/parameter_client.hpp>
37 if (yaw_goal_tolerance >= 0)
48 RCLCPP_INFO_STREAM(
getLogger(),
"[CbAbsoluteRotate] Absolute yaw Angle:" << goal_angle);
60 plannerSwitcher->setDefaultPlanners();
67 auto currentPoseMsg = p->toPoseMsg();
70 goal.pose.header.frame_id = referenceFrame;
71 goal.pose.header.stamp =
getNode()->now();
73 auto targetAngle = goal_angle * M_PI / 180.0;
74 goal.pose.pose.position = currentPoseMsg.position;
76 q.setRPY(0, 0, targetAngle);
77 goal.pose.pose.orientation = tf2::toMsg(q);
80 if (odomTracker_ !=
nullptr)
83 odomTracker_->pushPath(pathname);
84 odomTracker_->setStartPoint(p->toPoseStampedMsg());
93 "[CbAbsoluteRotate] current pose yaw: " << tf2::getYaw(currentPoseMsg.orientation));
95 getLogger(),
"[CbAbsoluteRotate] goal pose yaw: " << tf2::getYaw(goal.pose.pose.orientation));
103 std::string nodename =
"/controller_server";
105 auto parameters_client =
106 std::make_shared<rclcpp::AsyncParametersClient>(this->
getNode(), nodename);
109 log,
"[CbAbsoluteRotate] using a parameter client to update some controller parameters: "
110 << nodename <<
". Waiting service.");
111 parameters_client->wait_for_service();
113 RCLCPP_INFO_STREAM(log,
"[CbAbsoluteRotate] Service found: " << nodename <<
".");
115 std::string localPlannerName;
116 std::vector<rclcpp::Parameter> parameters;
119 rclcpp::Parameter yaw_goal_tolerance(
"goal_checker.yaw_goal_tolerance");
121 rclcpp::Parameter max_vel_theta, min_vel_theta;
127 if (isPureSpinningPlanner)
129 localPlannerName =
"PureSpinningLocalPlanner";
130 max_vel_theta = rclcpp::Parameter(localPlannerName +
".max_angular_z_speed");
131 min_vel_theta = rclcpp::Parameter(localPlannerName +
".min_vel_theta");
133 else if (isRosBasePlanner)
135 localPlannerName =
"FollowPath";
136 max_vel_theta = rclcpp::Parameter(localPlannerName +
".max_vel_theta");
137 min_vel_theta = rclcpp::Parameter(localPlannerName +
".min_vel_theta");
145 auto fut = parameters_client->get_parameters(
146 {localPlannerName +
".yaw_goal_tolerance"}, [&](
auto futureParameters) {
147 auto params = futureParameters.get();
154 yaw_goal_tolerance = rclcpp::Parameter(
"goal_checker.yaw_goal_tolerance", *
yawGoalTolerance);
155 parameters.push_back(yaw_goal_tolerance);
158 "[CbAbsoluteRotate] updating yaw tolerance local planner to: %lf, from previous value: "
165 if (isRosBasePlanner)
171 auto fut = parameters_client->get_parameters(
172 {localPlannerName +
".max_vel_theta"}, [&](
auto futureParameters) {
173 auto params = futureParameters.get();
181 max_vel_theta = rclcpp::Parameter(localPlannerName +
".max_vel_theta", *
maxVelTheta);
182 min_vel_theta = rclcpp::Parameter(localPlannerName +
".min_vel_theta", -*
maxVelTheta);
183 parameters.push_back(max_vel_theta);
184 parameters.push_back(min_vel_theta);
188 "[CbAbsoluteRotate] updating max vel theta local planner to: %lf, from previous value: "
193 "[CbAbsoluteRotate] updating min vel theta local planner to: %lf, from previous value: "
202 yaw_goal_tolerance = rclcpp::Parameter(
"goal_checker.yaw_goal_tolerance",
oldYawTolerance);
205 "[CbAbsoluteRotate] restoring yaw tolerance local planner from: %lf, to previous value: "
212 if (isRosBasePlanner)
214 max_vel_theta = rclcpp::Parameter(localPlannerName +
".max_vel_theta",
oldMaxVelTheta);
215 min_vel_theta = rclcpp::Parameter(localPlannerName +
".max_vel_theta",
oldMinVelTheta);
218 parameters.push_back(max_vel_theta);
219 parameters.push_back(min_vel_theta);
222 "[CbAbsoluteRotate] restoring max vel theta local planner from: %lf, to previous value: "
227 "[CbAbsoluteRotate] restoring min vel theta local planner from: %lf, to previous value: "
233 if (parameters.size())
235 std::stringstream ss;
236 ss <<
"Executing asynchronous request. Parameters to update: " << std::endl;
237 for (
auto & p : parameters)
239 ss << p.get_name() <<
" - " << p.value_to_string() << std::endl;
242 RCLCPP_INFO_STREAM(
getLogger(),
"[CbAbsoluteRotate] " << ss.str());
244 auto futureResults = parameters_client->set_parameters(parameters);
247 for (
auto & res : futureResults.get())
250 getLogger(),
"[CbAbsoluteRotate] parameter result: " << parameters[i].get_name() <<
"="
251 << parameters[i].as_string()
252 <<
". Result: " << res.successful);
256 RCLCPP_INFO(log,
"[CbAbsoluteRotate] parameters updated");
260 RCLCPP_INFO(log,
"[CbAbsoluteRotate] skipping parameters update");
std::optional< float > maxVelTheta
std::optional< SpinningPlanner > spinningPlanner
void updateTemporalBehaviorParameters(bool undo)
float absoluteGoalAngleDegree
std::shared_ptr< tf2_ros::Buffer > listener
std::optional< float > yawGoalTolerance
cl_nav2z::ClNav2Z * moveBaseClient_
void setGoalCheckerId(std::string goal_checker_id)
void setPureSpinningPlanner()
const std::string & getReferenceFrame() const
ISmaccState * getCurrentState()
std::string getName() const
virtual rclcpp::Logger getLogger()
virtual rclcpp::Node::SharedPtr getNode()
TComponent * getComponent()
virtual std::string getName()=0
std::shared_future< typename GoalHandle::SharedPtr > sendGoal(Goal &goal)
typename ActionClient::Goal Goal