SMACC2
Loading...
Searching...
No Matches
cp_odom_tracker.cpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20#include <cl_nav2z/common.hpp>
21
22#include <angles/angles.h>
23#include <tf2/utils.h>
25#include <smacc2/component.hpp>
27
28#include <boost/range/adaptor/reversed.hpp>
29
30namespace cl_nav2z
31{
32namespace odom_tracker
33{
34using namespace smacc2;
35
37 std::string odomTopicName, std::string odomFrame, OdomTrackerStrategy strategy)
38: strategy_(strategy)
39{
41 publishMessages = true;
42 odomFrame_ = odomFrame;
43 odomTopicName_ = odomTopicName;
44}
45
46template <typename T>
48 rclcpp::Node::SharedPtr & node, std::string param_name, T & value)
49{
50 if (!node->get_parameter(param_name, value))
51 {
52 RCLCPP_INFO_STREAM(
53 node->get_logger(), "[CpOdomTracker] autoset " << param_name << ": " << value);
54 node->declare_parameter(param_name, value);
55 }
56 else
57 {
58 RCLCPP_INFO_STREAM(node->get_logger(), "[CpOdomTracker] " << param_name << ": " << value);
59 }
60}
61
63{
64 // default values
65 recordPointDistanceThreshold_ = 0.005; // 5 mm
66 recordAngularDistanceThreshold_ = 0.1; // radians
67 clearPointDistanceThreshold_ = 0.05; // 5 cm
69
70 auto nh = getNode();
71 RCLCPP_WARN(getLogger(), "[CpOdomTracker] Initializing Odometry Tracker");
72
73 parameterDeclareAndtryGetOrSet(nh, "odom_frame", this->odomFrame_);
75 nh, "record_point_distance_threshold", recordPointDistanceThreshold_);
77 nh, "record_angular_distance_threshold", recordAngularDistanceThreshold_);
79 nh, "clear_point_distance_threshold", clearPointDistanceThreshold_);
81 nh, "clear_angular_distance_threshold", clearAngularDistanceThreshold_);
82
83 param_callback_handle_ = getNode()->add_on_set_parameters_callback(
84 std::bind(&CpOdomTracker::parametersCallback, this, std::placeholders::_1));
85
87 nh->create_publisher<nav_msgs::msg::Path>("odom_tracker_path", rclcpp::QoS(1));
88
90 nh->create_publisher<nav_msgs::msg::Path>("odom_tracker_stacked_path", rclcpp::QoS(1));
91
93 {
94 RCLCPP_INFO_STREAM(
95 nh->get_logger(), "[CpOdomTracker] subscribing to odom topic: " << odomTopicName_);
96
97 rclcpp::SensorDataQoS qos;
98 odomSub_ = nh->create_subscription<nav_msgs::msg::Odometry>(
99 odomTopicName_, qos,
100 std::bind(&CpOdomTracker::odomMessageCallback, this, std::placeholders::_1));
101 }
103 {
104 this->requiresComponent(robotPose_, ComponentRequirement::HARD);
105 robotPoseTimer_ = nh->create_wall_timer(
106 std::chrono::milliseconds(100), std::bind(&CpOdomTracker::update, this));
107 }
108 else
109 {
110 RCLCPP_ERROR_STREAM(
111 nh->get_logger(), "[CpOdomTracker] unknown strategy: " << (int)this->strategy_);
112 }
113}
114
120rcl_interfaces::msg::SetParametersResult CpOdomTracker::parametersCallback(
121 const std::vector<rclcpp::Parameter> & parameters)
122{
123 std::lock_guard<std::mutex> lock(m_mutex_);
124 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex acquire");
125
126 for (const auto & param : parameters)
127 {
128 if (param.get_name() == "record_point_distance_threshold")
129 {
130 recordPointDistanceThreshold_ = param.as_double();
131 }
132 else if (param.get_name() == "record_angular_distance_threshold")
133 {
134 recordAngularDistanceThreshold_ = param.as_double();
135 }
136 else if (param.get_name() == "clear_point_distance_threshold")
137 {
138 clearPointDistanceThreshold_ = param.as_double();
139 }
140 else if (param.get_name() == "clear_angular_distance_threshold")
141 {
142 clearAngularDistanceThreshold_ = param.as_double();
143 }
144 else if (param.get_name() == "odom_frame")
145 {
146 odomFrame_ = param.as_string();
147 }
148 }
149
150 rcl_interfaces::msg::SetParametersResult result;
151 result.successful = true;
152 result.reason = "success";
153 return result;
154}
155
162{
163 std::lock_guard<std::mutex> lock(m_mutex_);
164
165 switch (workingMode)
166 {
168 RCLCPP_INFO_STREAM(
169 getLogger(),
170 "[CpOdomTracker] setting working mode to RECORD - record_point_distance_threshold: "
172 << ", record_angular_distance_threshold: " << recordAngularDistanceThreshold_);
173 break;
175 RCLCPP_INFO_STREAM(
176 getLogger(),
177 "[CpOdomTracker] setting working mode to CLEAR - clear_point_distance_threshold: "
179 << ", clear_angular_distance_threshold: " << clearAngularDistanceThreshold_);
180 break;
182 RCLCPP_INFO_STREAM(getLogger(), "[CpOdomTracker] setting working mode to IDLE");
183 break;
184 default:
185
186 RCLCPP_INFO_STREAM(getLogger(), "[CpOdomTracker] setting working mode to <UNKNOWN>");
187 }
188
189 if (this->odomSub_ != nullptr && this->odomSub_->get_publisher_count() == 0)
190 {
191 RCLCPP_ERROR_STREAM(
192 getLogger(),
193 "[CpOdomTracker] Odom tracker cannot record the path because there is no publisher to the "
194 "odometry topic");
195 }
196
197 workingMode_ = workingMode;
198 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex release");
199}
200
207{
208 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex acquire");
209 std::lock_guard<std::mutex> lock(m_mutex_);
210 publishMessages = value;
211 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex release");
213}
214
215void CpOdomTracker::pushPath() { this->pushPath(std::string()); }
216
217void CpOdomTracker::pushPath(std::string pathname)
218{
219 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex acquire, to push path");
220 std::lock_guard<std::mutex> lock(m_mutex_);
221
222 this->logStateString(false);
223 if (this->odomSub_ != nullptr && this->odomSub_->get_publisher_count() == 0)
224 {
225 RCLCPP_ERROR_STREAM(
226 getLogger(),
227 "[CpOdomTracker] Odom tracker cannot record the path because there is no publisher to the "
228 "odometry topic");
229 }
230
232 pathStack_.push_back(baseTrajectory_);
233
234 geometry_msgs::msg::PoseStamped goalPose;
235 if (this->currentMotionGoal_) goalPose = *this->currentMotionGoal_;
236
237 RCLCPP_INFO_STREAM(
238 getLogger(), "[CpOdomTracker] currentPathName: " << pathname
239 << " size: " << baseTrajectory_.poses.size()
240 << " current motion goal: " << goalPose);
241
242 currentPathName_ = pathname;
243
244 // clean the current trajectory to start a new one
245 baseTrajectory_.poses.clear();
246
247 this->logStateString(false);
249
250 this->currentMotionGoal_.reset();
251}
252
253void CpOdomTracker::popPath(int popCount, bool keepPreviousPath)
254{
255 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex acquire to pop path");
256 std::lock_guard<std::mutex> lock(m_mutex_);
257
258 RCLCPP_INFO(getLogger(), "POP PATH ENTRY");
259 this->logStateString();
260
261 if (this->odomSub_ != nullptr && this->odomSub_->get_publisher_count() == 0)
262 {
263 RCLCPP_ERROR_STREAM(
264 getLogger(),
265 "[CpOdomTracker] Odom tracker cannot record the path because there is no publisher to the "
266 "odometry topic");
267 }
268
269 if (!keepPreviousPath)
270 {
271 baseTrajectory_.poses.clear();
272 }
273
274 while (popCount > 0 && !pathStack_.empty())
275 {
276 auto & stackedPath = pathStack_.back().poses;
277 auto & stackedPathInfo = pathInfos_.back();
278
279 baseTrajectory_.poses.insert(
280 baseTrajectory_.poses.begin(), stackedPath.begin(), stackedPath.end());
281 this->currentMotionGoal_ = stackedPathInfo.goalPose;
282 pathStack_.pop_back();
283 pathInfos_.pop_back();
284 popCount--;
285
286 RCLCPP_INFO(getLogger(), "POP PATH Iteration ");
287 this->logStateString();
288 }
289
290 RCLCPP_INFO(getLogger(), "POP PATH EXITING");
291 this->logStateString();
292 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex release");
294
295 this->currentMotionGoal_.reset();
296}
297
299{
300 std::stringstream ss;
301 ss << "--- odom tracker state ---" << std::endl;
302 ss
303 << " - path stack -" << currentPathName_ << " - size:"
304 << pathStack_.size()
305 //<< " goal: " << (getCurrentMotionGoal()? getCurrentMotionGoal()->pose: geometry_msgs::msg::Pose())
306 << std::endl;
307 ss << " - [STACK-HEAD active path size: " << baseTrajectory_.poses.size() << "]" << std::endl;
308 int i = 0;
309 for (auto & p : pathStack_ | boost::adaptors::reversed)
310 {
311 auto & pathinfo = pathInfos_[pathInfos_.size() - i - 1];
312 std::string goalstr = "[]";
313 if (pathinfo.goalPose)
314 {
315 std::stringstream ss;
316 ss << *(pathinfo.goalPose);
317 goalstr = ss.str();
318 }
319
320 ss << " - p " << i << "[" << p.header.stamp << "], size: " << p.poses.size() << " - "
321 << pathinfo.name << " - goal: " << goalstr << std::endl;
322 i++;
323 }
324 ss << "---";
325
326 if (this->odomSub_ != nullptr && this->odomSub_->get_publisher_count() == 0)
327 {
328 ss << std::endl
329 << "[CpOdomTracker] Odom tracker cannot record the path because there is no publisher to "
330 "the odometry topic"
331 << std::endl;
332 }
333
334 if (debug)
335 RCLCPP_DEBUG(getLogger(), ss.str().c_str());
336 else
337 RCLCPP_INFO(getLogger(), ss.str().c_str());
338}
339
341{
342 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex acquire to clear path");
343 std::lock_guard<std::mutex> lock(m_mutex_);
344 baseTrajectory_.poses.clear();
345
346 rtPublishPaths(getNode()->now());
347 this->logStateString();
349
350 this->currentMotionGoal_.reset();
351}
352
353void CpOdomTracker::setCurrentPathName(const std::string & currentPathName)
354{
355 RCLCPP_INFO_STREAM(getLogger(), "[CpOdomTracker] set current path name: " << currentPathName);
356 currentPathName_ = currentPathName;
357}
358
359void CpOdomTracker::setStartPoint(const geometry_msgs::msg::PoseStamped & pose)
360{
361 std::lock_guard<std::mutex> lock(m_mutex_);
362 RCLCPP_INFO_STREAM(getLogger(), "[CpOdomTracker] set current path starting point: " << pose);
363 if (baseTrajectory_.poses.size() > 0)
364 {
365 baseTrajectory_.poses[0] = pose;
366 }
367 else
368 {
369 baseTrajectory_.poses.push_back(pose);
370 }
372}
373
374void CpOdomTracker::setStartPoint(const geometry_msgs::msg::Pose & pose)
375{
376 std::lock_guard<std::mutex> lock(m_mutex_);
377 RCLCPP_INFO_STREAM(getLogger(), "[CpOdomTracker] set current path starting point: " << pose);
378 geometry_msgs::msg::PoseStamped posestamped;
379 posestamped.header.frame_id = this->odomFrame_;
380 posestamped.header.stamp = getNode()->now();
381 posestamped.pose = pose;
382
383 if (baseTrajectory_.poses.size() > 0)
384 {
385 baseTrajectory_.poses[0] = posestamped;
386 }
387 else
388 {
389 baseTrajectory_.poses.push_back(posestamped);
390 }
392}
393
394void CpOdomTracker::setCurrentMotionGoal(const geometry_msgs::msg::PoseStamped & pose)
395{
396 std::lock_guard<std::mutex> lock(m_mutex_);
397 this->currentMotionGoal_ = pose;
398}
399
400std::optional<geometry_msgs::msg::PoseStamped> CpOdomTracker::getCurrentMotionGoal()
401{
402 std::lock_guard<std::mutex> lock(m_mutex_);
403 return this->currentMotionGoal_;
404}
405
406nav_msgs::msg::Path CpOdomTracker::getPath()
407{
408 std::lock_guard<std::mutex> lock(m_mutex_);
409 return this->baseTrajectory_;
410}
411
417void CpOdomTracker::rtPublishPaths(rclcpp::Time timestamp)
418{
419 baseTrajectory_.header.stamp = timestamp;
421
422 aggregatedStackPathMsg_.header.stamp = timestamp;
424}
425
427{
428 aggregatedStackPathMsg_.poses.clear();
429 for (auto & p : pathStack_)
430 {
431 aggregatedStackPathMsg_.poses.insert(
432 aggregatedStackPathMsg_.poses.end(), p.poses.begin(), p.poses.end());
433 }
434
435 aggregatedStackPathMsg_.header.frame_id = this->odomFrame_;
436}
437
443bool CpOdomTracker::updateClearPath(const geometry_msgs::msg::PoseStamped & base_pose)
444{
445 // we initially accept any message if the queue is empty
447 baseTrajectory_.header = base_pose.header;
448
449 bool acceptBackward = false;
450 bool clearingError = false;
451 bool finished = false;
452
453 while (!finished)
454 {
455 if (
456 baseTrajectory_.poses.size() <=
457 1) // we at least keep always the first point of the forward path when clearing
458 // (this is important for backwards planner replanning and not losing the
459 // last goal)
460 {
461 acceptBackward = false;
462 finished = true;
463 }
464 else
465 {
466 auto & carrotPose = baseTrajectory_.poses.back().pose;
467 auto & carrotPoint = carrotPose.position;
468
469 double carrotAngle = tf2::getYaw(carrotPose.orientation);
470
471 auto & currePose = base_pose.pose;
472 auto & currePoint = currePose.position;
473 double currentAngle = tf2::getYaw(currePose.orientation);
474
475 double lastpointdist = p2pDistance(carrotPoint, currePoint);
476 double goalAngleOffset = fabs(angles::shortest_angular_distance(carrotAngle, currentAngle));
477
478 acceptBackward = !baseTrajectory_.poses.empty() &&
479 lastpointdist < clearPointDistanceThreshold_ &&
480 goalAngleOffset < clearAngularDistanceThreshold_;
481
482 clearingError = lastpointdist > 2 * clearPointDistanceThreshold_;
483 RCLCPP_DEBUG_STREAM(
484 getLogger(), "[CpOdomTracker] clearing (accepted: " << acceptBackward
485 << ") linerr: " << lastpointdist
486 << ", anglerr: " << goalAngleOffset);
487 }
488
489 // RCLCPP_INFO(getLogger(),"Backwards, last distance: %lf < %lf accept: %d", dist,
490 // minPointDistanceBackwardThresh_, acceptBackward);
491 if (
492 acceptBackward &&
493 baseTrajectory_.poses.size() > 1) /* we always leave at least one item, specially interesting
494 for the backward local planner reach
495 the backwards goal with enough precision*/
496 {
497 baseTrajectory_.poses.pop_back();
498 }
499 else if (clearingError)
500 {
501 finished = true;
502 RCLCPP_WARN(getLogger(), "[CpOdomTracker] Incorrect odom clearing motion.");
503 }
504 else
505 {
506 finished = true;
508 }
509 }
510
511 return acceptBackward;
512}
513
519bool CpOdomTracker::updateRecordPath(const geometry_msgs::msg::PoseStamped & base_pose)
520{
522 baseTrajectory_.header = base_pose.header;
523
524 bool enqueueOdomMessage = false;
525
526 double dist = -1;
527 if (baseTrajectory_.poses.empty())
528 {
529 enqueueOdomMessage = true;
530 }
531 else
532 {
533 const auto & prevPose = baseTrajectory_.poses.back().pose;
534 const geometry_msgs::msg::Point & prevPoint = prevPose.position;
535 double prevAngle = tf2::getYaw(prevPose.orientation);
536
537 const geometry_msgs::msg::Point & currePoint = base_pose.pose.position;
538 double currentAngle = tf2::getYaw(base_pose.pose.orientation);
539
540 dist = p2pDistance(prevPoint, currePoint);
541 double goalAngleOffset = fabs(angles::shortest_angular_distance(prevAngle, currentAngle));
542
543 // RCLCPP_WARN(getLogger(),"dist %lf vs min %lf", dist, recordPointDistanceThreshold_);
544
545 RCLCPP_WARN_THROTTLE(getLogger(), *getNode()->get_clock(), 2000, "odom received");
546
548 {
549 enqueueOdomMessage = true;
550 }
551 else
552 {
553 // RCLCPP_WARN(getLogger(),"skip odom, dist: %lf", dist);
554 enqueueOdomMessage = false;
555 }
556 }
557
558 if (enqueueOdomMessage)
559 {
560 RCLCPP_WARN_THROTTLE(
561 getLogger(), *getNode()->get_clock(), 2000, "enqueue odom tracker pose. dist %lf vs min %lf",
563 baseTrajectory_.poses.push_back(base_pose);
564 }
565
566 return enqueueOdomMessage;
567}
568
575{
576 return;
577
578 if (!getNode()->get_parameter("odom_frame", this->odomFrame_))
579 {
580 }
581
582 if (!getNode()->get_parameter("record_point_distance_threshold", recordPointDistanceThreshold_))
583 {
584 }
585
586 if (!getNode()->get_parameter(
587 "record_angular_distance_threshold", recordAngularDistanceThreshold_))
588 {
589 }
590
591 if (!getNode()->get_parameter("clear_point_distance_threshold", clearPointDistanceThreshold_))
592 {
593 }
594
595 if (!getNode()->get_parameter("clear_angular_distance_threshold", clearAngularDistanceThreshold_))
596 {
597 }
598}
599
606{
607 RCLCPP_INFO(getLogger(), "odom_tracker update");
608 auto pose = robotPose_->toPoseStampedMsg();
609 RCLCPP_INFO(getLogger(), "odom tracker updatd pose, frame: %s", pose.header.frame_id.c_str());
610 processNewPose(pose);
611 RCLCPP_INFO(getLogger(), "odom_tracker update end");
612}
613
619void CpOdomTracker::odomMessageCallback(const nav_msgs::msg::Odometry::SharedPtr odom)
620{
621 geometry_msgs::msg::PoseStamped base_pose;
622 base_pose.pose = odom->pose.pose;
623 base_pose.header = odom->header;
624
625 processNewPose(base_pose);
626}
627
633void CpOdomTracker::processNewPose(const geometry_msgs::msg::PoseStamped & odom)
634{
635 RCLCPP_INFO_THROTTLE(
636 getLogger(), *getNode()->get_clock(), 5000,
637 "[odom_tracker] processing odom msg update heartbeat");
638 std::lock_guard<std::mutex> lock(m_mutex_);
639
641
643 {
644 updateRecordPath(odom);
645 }
647 {
648 updateClearPath(odom);
649 }
650
651 // RCLCPP_WARN(getLogger(),"odomTracker odometry callback");
652 if (publishMessages)
653 {
654 rtPublishPaths(odom.header.stamp);
655 }
656
657 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex release");
658}
659} // namespace odom_tracker
660} // namespace cl_nav2z
geometry_msgs::msg::PoseStamped toPoseStampedMsg()
Definition cp_pose.hpp:63
void popPath(int pathCount=1, bool keepPreviousPath=false)
virtual bool updateRecordPath(const geometry_msgs::msg::PoseStamped &odom)
rclcpp::Subscription< nav_msgs::msg::Odometry >::SharedPtr odomSub_
std::optional< geometry_msgs::msg::PoseStamped > currentMotionGoal_
virtual void processNewPose(const geometry_msgs::msg::PoseStamped &odom)
odom callback: Updates the path - this must be called periodically for each odometry message.
double recordPointDistanceThreshold_
How much distance there is between two points of the path.
nav_msgs::msg::Path baseTrajectory_
Processed path for the mouth of the reel.
virtual void rtPublishPaths(rclcpp::Time timestamp)
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr param_callback_handle_
void setCurrentPathName(const std::string &currentPathName)
virtual void odomMessageCallback(const nav_msgs::msg::Odometry::SharedPtr odom)
rclcpp::TimerBase::SharedPtr robotPoseTimer_
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr robotBasePathStackedPub_
void setCurrentMotionGoal(const geometry_msgs::msg::PoseStamped &pose)
virtual bool updateClearPath(const geometry_msgs::msg::PoseStamped &odom)
std::vector< nav_msgs::msg::Path > pathStack_
void setWorkingMode(WorkingMode workingMode)
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr robotBasePathPub_
rcl_interfaces::msg::SetParametersResult parametersCallback(const std::vector< rclcpp::Parameter > &parameters)
std::optional< geometry_msgs::msg::PoseStamped > getCurrentMotionGoal()
void setStartPoint(const geometry_msgs::msg::PoseStamped &pose)
CpOdomTracker(std::string odomtopicName="/odom", std::string odomFrame="odom", OdomTrackerStrategy strategy=OdomTrackerStrategy::ODOMETRY_SUBSCRIBER)
rclcpp::Logger getLogger() const
void requiresComponent(TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
rclcpp::Node::SharedPtr getNode()
double p2pDistance(const geometry_msgs::msg::Point &p1, const geometry_msgs::msg::Point &p2)
void parameterDeclareAndtryGetOrSet(rclcpp::Node::SharedPtr &node, std::string param_name, T &value)