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 ******************************************************************************************************************/
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{
35 std::string odomTopicName, std::string odomFrame, OdomTrackerStrategy strategy)
36: strategy_(strategy)
37{
39 publishMessages = true;
40 odomFrame_ = odomFrame;
41 odomTopicName_ = odomTopicName;
42}
43
44template <typename T>
46 rclcpp::Node::SharedPtr & node, std::string param_name, T & value)
47{
48 if (!node->get_parameter(param_name, value))
49 {
50 RCLCPP_INFO_STREAM(
51 node->get_logger(), "[CpOdomTracker] autoset " << param_name << ": " << value);
52 node->declare_parameter(param_name, value);
53 }
54 else
55 {
56 RCLCPP_INFO_STREAM(node->get_logger(), "[CpOdomTracker] " << param_name << ": " << value);
57 }
58}
59
61{
62 // default values
63 recordPointDistanceThreshold_ = 0.005; // 5 mm
64 recordAngularDistanceThreshold_ = 0.1; // radians
65 clearPointDistanceThreshold_ = 0.05; // 5 cm
67
68 auto nh = getNode();
69 RCLCPP_WARN(getLogger(), "[CpOdomTracker] Initializing Odometry Tracker");
70
71 parameterDeclareAndtryGetOrSet(nh, "odom_frame", this->odomFrame_);
73 nh, "record_point_distance_threshold", recordPointDistanceThreshold_);
75 nh, "record_angular_distance_threshold", recordAngularDistanceThreshold_);
77 nh, "clear_point_distance_threshold", clearPointDistanceThreshold_);
79 nh, "clear_angular_distance_threshold", clearAngularDistanceThreshold_);
80
81 param_callback_handle_ = getNode()->add_on_set_parameters_callback(
82 std::bind(&CpOdomTracker::parametersCallback, this, std::placeholders::_1));
83
85 nh->create_publisher<nav_msgs::msg::Path>("odom_tracker_path", rclcpp::QoS(1));
86
88 nh->create_publisher<nav_msgs::msg::Path>("odom_tracker_stacked_path", rclcpp::QoS(1));
89
91 {
92 RCLCPP_INFO_STREAM(
93 nh->get_logger(), "[CpOdomTracker] subscribing to odom topic: " << odomTopicName_);
94
95 rclcpp::SensorDataQoS qos;
96 odomSub_ = nh->create_subscription<nav_msgs::msg::Odometry>(
97 odomTopicName_, qos,
98 std::bind(&CpOdomTracker::odomMessageCallback, this, std::placeholders::_1));
99 }
101 {
103 robotPoseTimer_ = nh->create_wall_timer(
104 std::chrono::milliseconds(100), std::bind(&CpOdomTracker::update, this));
105 }
106 else
107 {
108 RCLCPP_ERROR_STREAM(
109 nh->get_logger(), "[CpOdomTracker] unknown strategy: " << (int)this->strategy_);
110 }
111}
112
118rcl_interfaces::msg::SetParametersResult CpOdomTracker::parametersCallback(
119 const std::vector<rclcpp::Parameter> & parameters)
120{
121 std::lock_guard<std::mutex> lock(m_mutex_);
122 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex acquire");
123
124 for (const auto & param : parameters)
125 {
126 if (param.get_name() == "record_point_distance_threshold")
127 {
128 recordPointDistanceThreshold_ = param.as_double();
129 }
130 else if (param.get_name() == "record_angular_distance_threshold")
131 {
132 recordAngularDistanceThreshold_ = param.as_double();
133 }
134 else if (param.get_name() == "clear_point_distance_threshold")
135 {
136 clearPointDistanceThreshold_ = param.as_double();
137 }
138 else if (param.get_name() == "clear_angular_distance_threshold")
139 {
140 clearAngularDistanceThreshold_ = param.as_double();
141 }
142 else if (param.get_name() == "odom_frame")
143 {
144 odomFrame_ = param.as_string();
145 }
146 }
147
148 rcl_interfaces::msg::SetParametersResult result;
149 result.successful = true;
150 result.reason = "success";
151 return result;
152}
153
160{
161 std::lock_guard<std::mutex> lock(m_mutex_);
162
163 switch (workingMode)
164 {
166 RCLCPP_INFO_STREAM(
167 getLogger(),
168 "[CpOdomTracker] setting working mode to RECORD - record_point_distance_threshold: "
170 << ", record_angular_distance_threshold: " << recordAngularDistanceThreshold_);
171 break;
173 RCLCPP_INFO_STREAM(
174 getLogger(),
175 "[CpOdomTracker] setting working mode to CLEAR - clear_point_distance_threshold: "
177 << ", clear_angular_distance_threshold: " << clearAngularDistanceThreshold_);
178 break;
180 RCLCPP_INFO_STREAM(getLogger(), "[CpOdomTracker] setting working mode to IDLE");
181 break;
182 default:
183
184 RCLCPP_INFO_STREAM(getLogger(), "[CpOdomTracker] setting working mode to <UNKNOWN>");
185 }
186
187 if (this->odomSub_ != nullptr && this->odomSub_->get_publisher_count() == 0)
188 {
189 RCLCPP_ERROR_STREAM(
190 getLogger(),
191 "[CpOdomTracker] Odom tracker cannot record the path because there is no publisher to the "
192 "odometry topic");
193 }
194
195 workingMode_ = workingMode;
196 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex release");
197}
198
205{
206 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex acquire");
207 std::lock_guard<std::mutex> lock(m_mutex_);
208 publishMessages = value;
209 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex release");
211}
212
213void CpOdomTracker::pushPath() { this->pushPath(std::string()); }
214
215void CpOdomTracker::pushPath(std::string pathname)
216{
217 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex acquire, to push path");
218 std::lock_guard<std::mutex> lock(m_mutex_);
219
220 this->logStateString(false);
221 if (this->odomSub_ != nullptr && this->odomSub_->get_publisher_count() == 0)
222 {
223 RCLCPP_ERROR_STREAM(
224 getLogger(),
225 "[CpOdomTracker] Odom tracker cannot record the path because there is no publisher to the "
226 "odometry topic");
227 }
228
230 pathStack_.push_back(baseTrajectory_);
231
232 geometry_msgs::msg::PoseStamped goalPose;
233 if (this->currentMotionGoal_) goalPose = *this->currentMotionGoal_;
234
235 RCLCPP_INFO_STREAM(
236 getLogger(), "[CpOdomTracker] currentPathName: " << pathname
237 << " size: " << baseTrajectory_.poses.size()
238 << " current motion goal: " << goalPose);
239
240 currentPathName_ = pathname;
241
242 // clean the current trajectory to start a new one
243 baseTrajectory_.poses.clear();
244
245 this->logStateString(false);
247
248 this->currentMotionGoal_.reset();
249}
250
251void CpOdomTracker::popPath(int popCount, bool keepPreviousPath)
252{
253 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex acquire to pop path");
254 std::lock_guard<std::mutex> lock(m_mutex_);
255
256 RCLCPP_INFO(getLogger(), "POP PATH ENTRY");
257 this->logStateString();
258
259 if (this->odomSub_ != nullptr && this->odomSub_->get_publisher_count() == 0)
260 {
261 RCLCPP_ERROR_STREAM(
262 getLogger(),
263 "[CpOdomTracker] Odom tracker cannot record the path because there is no publisher to the "
264 "odometry topic");
265 }
266
267 if (!keepPreviousPath)
268 {
269 baseTrajectory_.poses.clear();
270 }
271
272 while (popCount > 0 && !pathStack_.empty())
273 {
274 auto & stackedPath = pathStack_.back().poses;
275 auto & stackedPathInfo = pathInfos_.back();
276
277 baseTrajectory_.poses.insert(
278 baseTrajectory_.poses.begin(), stackedPath.begin(), stackedPath.end());
279 this->currentMotionGoal_ = stackedPathInfo.goalPose;
280 pathStack_.pop_back();
281 pathInfos_.pop_back();
282 popCount--;
283
284 RCLCPP_INFO(getLogger(), "POP PATH Iteration ");
285 this->logStateString();
286 }
287
288 RCLCPP_INFO(getLogger(), "POP PATH EXITING");
289 this->logStateString();
290 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex release");
292
293 this->currentMotionGoal_.reset();
294}
295
297{
298 std::stringstream ss;
299 ss << "--- odom tracker state ---" << std::endl;
300 ss
301 << " - path stack -" << currentPathName_ << " - size:"
302 << pathStack_.size()
303 //<< " goal: " << (getCurrentMotionGoal()? getCurrentMotionGoal()->pose: geometry_msgs::msg::Pose())
304 << std::endl;
305 ss << " - [STACK-HEAD active path size: " << baseTrajectory_.poses.size() << "]" << std::endl;
306 int i = 0;
307 for (auto & p : pathStack_ | boost::adaptors::reversed)
308 {
309 auto & pathinfo = pathInfos_[pathInfos_.size() - i - 1];
310 std::string goalstr = "[]";
311 if (pathinfo.goalPose)
312 {
313 std::stringstream ss;
314 ss << *(pathinfo.goalPose);
315 goalstr = ss.str();
316 }
317
318 ss << " - p " << i << "[" << p.header.stamp << "], size: " << p.poses.size() << " - "
319 << pathinfo.name << " - goal: " << goalstr << std::endl;
320 i++;
321 }
322 ss << "---";
323
324 if (this->odomSub_ != nullptr && this->odomSub_->get_publisher_count() == 0)
325 {
326 ss << std::endl
327 << "[CpOdomTracker] Odom tracker cannot record the path because there is no publisher to "
328 "the odometry topic"
329 << std::endl;
330 }
331
332 if (debug)
333 RCLCPP_DEBUG(getLogger(), ss.str().c_str());
334 else
335 RCLCPP_INFO(getLogger(), ss.str().c_str());
336}
337
339{
340 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex acquire to clear path");
341 std::lock_guard<std::mutex> lock(m_mutex_);
342 baseTrajectory_.poses.clear();
343
344 rtPublishPaths(getNode()->now());
345 this->logStateString();
347
348 this->currentMotionGoal_.reset();
349}
350
351void CpOdomTracker::setCurrentPathName(const std::string & currentPathName)
352{
353 RCLCPP_INFO_STREAM(getLogger(), "[CpOdomTracker] set current path name: " << currentPathName);
354 currentPathName_ = currentPathName;
355}
356
357void CpOdomTracker::setStartPoint(const geometry_msgs::msg::PoseStamped & pose)
358{
359 std::lock_guard<std::mutex> lock(m_mutex_);
360 RCLCPP_INFO_STREAM(getLogger(), "[CpOdomTracker] set current path starting point: " << pose);
361 if (baseTrajectory_.poses.size() > 0)
362 {
363 baseTrajectory_.poses[0] = pose;
364 }
365 else
366 {
367 baseTrajectory_.poses.push_back(pose);
368 }
370}
371
372void CpOdomTracker::setStartPoint(const geometry_msgs::msg::Pose & pose)
373{
374 std::lock_guard<std::mutex> lock(m_mutex_);
375 RCLCPP_INFO_STREAM(getLogger(), "[CpOdomTracker] set current path starting point: " << pose);
376 geometry_msgs::msg::PoseStamped posestamped;
377 posestamped.header.frame_id = this->odomFrame_;
378 posestamped.header.stamp = getNode()->now();
379 posestamped.pose = pose;
380
381 if (baseTrajectory_.poses.size() > 0)
382 {
383 baseTrajectory_.poses[0] = posestamped;
384 }
385 else
386 {
387 baseTrajectory_.poses.push_back(posestamped);
388 }
390}
391
392void CpOdomTracker::setCurrentMotionGoal(const geometry_msgs::msg::PoseStamped & pose)
393{
394 std::lock_guard<std::mutex> lock(m_mutex_);
395 this->currentMotionGoal_ = pose;
396}
397
398std::optional<geometry_msgs::msg::PoseStamped> CpOdomTracker::getCurrentMotionGoal()
399{
400 std::lock_guard<std::mutex> lock(m_mutex_);
401 return this->currentMotionGoal_;
402}
403
404nav_msgs::msg::Path CpOdomTracker::getPath()
405{
406 std::lock_guard<std::mutex> lock(m_mutex_);
407 return this->baseTrajectory_;
408}
409
415void CpOdomTracker::rtPublishPaths(rclcpp::Time timestamp)
416{
417 baseTrajectory_.header.stamp = timestamp;
419
420 aggregatedStackPathMsg_.header.stamp = timestamp;
422}
423
425{
426 aggregatedStackPathMsg_.poses.clear();
427 for (auto & p : pathStack_)
428 {
429 aggregatedStackPathMsg_.poses.insert(
430 aggregatedStackPathMsg_.poses.end(), p.poses.begin(), p.poses.end());
431 }
432
433 aggregatedStackPathMsg_.header.frame_id = this->odomFrame_;
434}
435
441bool CpOdomTracker::updateClearPath(const geometry_msgs::msg::PoseStamped & base_pose)
442{
443 // we initially accept any message if the queue is empty
445 baseTrajectory_.header = base_pose.header;
446
447 bool acceptBackward = false;
448 bool clearingError = false;
449 bool finished = false;
450
451 while (!finished)
452 {
453 if (
454 baseTrajectory_.poses.size() <=
455 1) // we at least keep always the first point of the forward path when clearing
456 // (this is important for backwards planner replanning and not losing the
457 // last goal)
458 {
459 acceptBackward = false;
460 finished = true;
461 }
462 else
463 {
464 auto & carrotPose = baseTrajectory_.poses.back().pose;
465 auto & carrotPoint = carrotPose.position;
466
467 double carrotAngle = tf2::getYaw(carrotPose.orientation);
468
469 auto & currePose = base_pose.pose;
470 auto & currePoint = currePose.position;
471 double currentAngle = tf2::getYaw(currePose.orientation);
472
473 double lastpointdist = p2pDistance(carrotPoint, currePoint);
474 double goalAngleOffset = fabs(angles::shortest_angular_distance(carrotAngle, currentAngle));
475
476 acceptBackward = !baseTrajectory_.poses.empty() &&
477 lastpointdist < clearPointDistanceThreshold_ &&
478 goalAngleOffset < clearAngularDistanceThreshold_;
479
480 clearingError = lastpointdist > 2 * clearPointDistanceThreshold_;
481 RCLCPP_DEBUG_STREAM(
482 getLogger(), "[CpOdomTracker] clearing (accepted: " << acceptBackward
483 << ") linerr: " << lastpointdist
484 << ", anglerr: " << goalAngleOffset);
485 }
486
487 // RCLCPP_INFO(getLogger(),"Backwards, last distance: %lf < %lf accept: %d", dist,
488 // minPointDistanceBackwardThresh_, acceptBackward);
489 if (
490 acceptBackward &&
491 baseTrajectory_.poses.size() > 1) /* we always leave at least one item, specially interesting
492 for the backward local planner reach
493 the backwards goal with enough precision*/
494 {
495 baseTrajectory_.poses.pop_back();
496 }
497 else if (clearingError)
498 {
499 finished = true;
500 RCLCPP_WARN(getLogger(), "[CpOdomTracker] Incorrect odom clearing motion.");
501 }
502 else
503 {
504 finished = true;
506 }
507 }
508
509 return acceptBackward;
510}
511
517bool CpOdomTracker::updateRecordPath(const geometry_msgs::msg::PoseStamped & base_pose)
518{
520 baseTrajectory_.header = base_pose.header;
521
522 bool enqueueOdomMessage = false;
523
524 double dist = -1;
525 if (baseTrajectory_.poses.empty())
526 {
527 enqueueOdomMessage = true;
528 }
529 else
530 {
531 const auto & prevPose = baseTrajectory_.poses.back().pose;
532 const geometry_msgs::msg::Point & prevPoint = prevPose.position;
533 double prevAngle = tf2::getYaw(prevPose.orientation);
534
535 const geometry_msgs::msg::Point & currePoint = base_pose.pose.position;
536 double currentAngle = tf2::getYaw(base_pose.pose.orientation);
537
538 dist = p2pDistance(prevPoint, currePoint);
539 double goalAngleOffset = fabs(angles::shortest_angular_distance(prevAngle, currentAngle));
540
541 // RCLCPP_WARN(getLogger(),"dist %lf vs min %lf", dist, recordPointDistanceThreshold_);
542
543 RCLCPP_WARN_THROTTLE(getLogger(), *getNode()->get_clock(), 2000, "odom received");
544
546 {
547 enqueueOdomMessage = true;
548 }
549 else
550 {
551 // RCLCPP_WARN(getLogger(),"skip odom, dist: %lf", dist);
552 enqueueOdomMessage = false;
553 }
554 }
555
556 if (enqueueOdomMessage)
557 {
558 RCLCPP_WARN_THROTTLE(
559 getLogger(), *getNode()->get_clock(), 2000, "enqueue odom tracker pose. dist %lf vs min %lf",
561 baseTrajectory_.poses.push_back(base_pose);
562 }
563
564 return enqueueOdomMessage;
565}
566
573{
574 return;
575
576 if (!getNode()->get_parameter("odom_frame", this->odomFrame_))
577 {
578 }
579
580 if (!getNode()->get_parameter("record_point_distance_threshold", recordPointDistanceThreshold_))
581 {
582 }
583
584 if (!getNode()->get_parameter(
585 "record_angular_distance_threshold", recordAngularDistanceThreshold_))
586 {
587 }
588
589 if (!getNode()->get_parameter("clear_point_distance_threshold", clearPointDistanceThreshold_))
590 {
591 }
592
593 if (!getNode()->get_parameter("clear_angular_distance_threshold", clearAngularDistanceThreshold_))
594 {
595 }
596}
597
604{
605 RCLCPP_INFO(getLogger(), "odom_tracker update");
606 auto pose = robotPose_->toPoseStampedMsg();
607 RCLCPP_INFO(getLogger(), "odom tracker updatd pose, frame: %s", pose.header.frame_id.c_str());
608 processNewPose(pose);
609 RCLCPP_INFO(getLogger(), "odom_tracker update end");
610}
611
617void CpOdomTracker::odomMessageCallback(const nav_msgs::msg::Odometry::SharedPtr odom)
618{
619 geometry_msgs::msg::PoseStamped base_pose;
620 base_pose.pose = odom->pose.pose;
621 base_pose.header = odom->header;
622
623 processNewPose(base_pose);
624}
625
631void CpOdomTracker::processNewPose(const geometry_msgs::msg::PoseStamped & odom)
632{
633 RCLCPP_INFO_THROTTLE(
634 getLogger(), *getNode()->get_clock(), 5000,
635 "[odom_tracker] processing odom msg update heartbeat");
636 std::lock_guard<std::mutex> lock(m_mutex_);
637
639
641 {
642 updateRecordPath(odom);
643 }
645 {
646 updateClearPath(odom);
647 }
648
649 // RCLCPP_WARN(getLogger(),"odomTracker odometry callback");
650 if (publishMessages)
651 {
652 rtPublishPaths(odom.header.stamp);
653 }
654
655 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex release");
656}
657} // namespace odom_tracker
658} // 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)
void requiresComponent(TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist=false)
rclcpp::Logger getLogger() const
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)