SMACC2
Loading...
Searching...
No Matches
Classes | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
cl_nav2z::odom_tracker::CpOdomTracker Class Reference

#include <cp_odom_tracker.hpp>

Inheritance diagram for cl_nav2z::odom_tracker::CpOdomTracker:
Inheritance graph
Collaboration diagram for cl_nav2z::odom_tracker::CpOdomTracker:
Collaboration graph

Classes

struct  PathInfo
 

Public Member Functions

 CpOdomTracker (std::string odomtopicName="/odom", std::string odomFrame="odom")
 
virtual void processOdometryMessage (const nav_msgs::msg::Odometry::SharedPtr odom)
 odom callback: Updates the path - this must be called periodically for each odometry message.
 
void setWorkingMode (WorkingMode workingMode)
 
void setPublishMessages (bool value)
 
void pushPath ()
 
void pushPath (std::string pathname)
 
void popPath (int pathCount=1, bool keepPreviousPath=false)
 
void clearPath ()
 
void setStartPoint (const geometry_msgs::msg::PoseStamped &pose)
 
void setStartPoint (const geometry_msgs::msg::Pose &pose)
 
void setCurrentMotionGoal (const geometry_msgs::msg::PoseStamped &pose)
 
void setCurrentPathName (const std::string &currentPathName)
 
std::optional< geometry_msgs::msg::PoseStamped > getCurrentMotionGoal ()
 
nav_msgs::msg::Path getPath ()
 
void logStateString (bool debug=true)
 
- Public Member Functions inherited from smacc2::ISmaccComponent
 ISmaccComponent ()
 
virtual ~ISmaccComponent ()
 
virtual std::string getName () const
 

Protected Member Functions

void onInitialize () override
 
void updateConfiguration ()
 
virtual void rtPublishPaths (rclcpp::Time timestamp)
 
virtual bool updateRecordPath (const nav_msgs::msg::Odometry &odom)
 
virtual bool updateClearPath (const nav_msgs::msg::Odometry &odom)
 
void updateAggregatedStackPath ()
 
- Protected Member Functions inherited from smacc2::ISmaccComponent
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
template<typename TComponent >
void requiresComponent (TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist=false)
 
template<typename TComponent >
void requiresComponent (std::string name, TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist=false)
 
template<typename TClient >
void requiresClient (TClient *&requiredClientStorage)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentTypecreateSiblingComponent (TArgs... targs)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentTypecreateSiblingNamedComponent (std::string name, TArgs... targs)
 
rclcpp::Node::SharedPtr getNode ()
 
rclcpp::Logger getLogger () const
 
ISmaccStateMachinegetStateMachine ()
 

Protected Attributes

rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr robotBasePathPub_
 
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr robotBasePathStackedPub_
 
rclcpp::Subscription< nav_msgs::msg::Odometry >::SharedPtr odomSub_
 
double recordPointDistanceThreshold_
 How much distance there is between two points of the path.
 
double recordAngularDistanceThreshold_
 Meters.
 
double clearPointDistanceThreshold_
 rads
 
double clearAngularDistanceThreshold_
 rads
 
std::string odomFrame_
 
std::string odomTopicName_
 
bool publishMessages
 
nav_msgs::msg::Path baseTrajectory_
 Processed path for the mouth of the reel.
 
WorkingMode workingMode_
 
std::vector< nav_msgs::msg::Path > pathStack_
 
std::vector< PathInfopathInfos_
 
nav_msgs::msg::Path aggregatedStackPathMsg_
 
bool subscribeToOdometryTopic_
 
std::optional< geometry_msgs::msg::PoseStamped > currentMotionGoal_
 
std::string currentPathName_
 
std::mutex m_mutex_
 
- Protected Attributes inherited from smacc2::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Detailed Description

This object tracks and saves the trajectories performed by the vehicle so that they can be used later to execute operations such as "undo motions"

Definition at line 53 of file cp_odom_tracker.hpp.

Constructor & Destructor Documentation

◆ CpOdomTracker()

cl_nav2z::odom_tracker::CpOdomTracker::CpOdomTracker ( std::string  odomtopicName = "/odom",
std::string  odomFrame = "odom" 
)

Member Function Documentation

◆ clearPath()

void cl_nav2z::odom_tracker::CpOdomTracker::clearPath ( )

Definition at line 248 of file cp_odom_tracker.cpp.

249{
250 std::lock_guard<std::mutex> lock(m_mutex_);
251 baseTrajectory_.poses.clear();
252
253 rtPublishPaths(getNode()->now());
254 this->logStateString();
256
257 this->currentMotionGoal_.reset();
258}
std::optional< geometry_msgs::msg::PoseStamped > currentMotionGoal_
nav_msgs::msg::Path baseTrajectory_
Processed path for the mouth of the reel.
virtual void rtPublishPaths(rclcpp::Time timestamp)
rclcpp::Node::SharedPtr getNode()

References baseTrajectory_, currentMotionGoal_, smacc2::ISmaccComponent::getNode(), logStateString(), m_mutex_, rtPublishPaths(), and updateAggregatedStackPath().

Referenced by cl_nav2z::CbNavigateBackwards::onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getCurrentMotionGoal()

std::optional< geometry_msgs::msg::PoseStamped > cl_nav2z::odom_tracker::CpOdomTracker::getCurrentMotionGoal ( )

Definition at line 306 of file cp_odom_tracker.cpp.

307{
308 std::lock_guard<std::mutex> lock(m_mutex_);
309 return this->currentMotionGoal_;
310}

References currentMotionGoal_, and m_mutex_.

Referenced by cl_nav2z::CbRetry< TCbRelativeMotion >::onEntry().

Here is the caller graph for this function:

◆ getPath()

nav_msgs::msg::Path cl_nav2z::odom_tracker::CpOdomTracker::getPath ( )

Definition at line 312 of file cp_odom_tracker.cpp.

313{
314 std::lock_guard<std::mutex> lock(m_mutex_);
315 return this->baseTrajectory_;
316}

References baseTrajectory_, and m_mutex_.

Referenced by cl_nav2z::CbUndoPathBackwards::onEntry().

Here is the caller graph for this function:

◆ logStateString()

void cl_nav2z::odom_tracker::CpOdomTracker::logStateString ( bool  debug = true)

Definition at line 214 of file cp_odom_tracker.cpp.

215{
216 std::stringstream ss;
217 ss << "--- odom tracker state ---" << std::endl;
218 ss
219 << " - path stack -" << currentPathName_ << " - size:"
220 << pathStack_.size()
221 //<< " goal: " << (getCurrentMotionGoal()? getCurrentMotionGoal()->pose: geometry_msgs::msg::Pose())
222 << std::endl;
223 ss << " - [STACK-HEAD active path size: " << baseTrajectory_.poses.size() << "]" << std::endl;
224 int i = 0;
225 for (auto & p : pathStack_ | boost::adaptors::reversed)
226 {
227 auto & pathinfo = pathInfos_[pathInfos_.size() - i - 1];
228 std::string goalstr = "[]";
229 if (pathinfo.goalPose)
230 {
231 std::stringstream ss;
232 ss << *(pathinfo.goalPose);
233 goalstr = ss.str();
234 }
235
236 ss << " - p " << i << "[" << p.header.stamp << "], size: " << p.poses.size() << " - "
237 << pathinfo.name << " - goal: " << goalstr << std::endl;
238 i++;
239 }
240 ss << "---";
241
242 if (debug)
243 RCLCPP_DEBUG(getLogger(), ss.str().c_str());
244 else
245 RCLCPP_INFO(getLogger(), ss.str().c_str());
246}
std::vector< nav_msgs::msg::Path > pathStack_
rclcpp::Logger getLogger() const

References baseTrajectory_, currentPathName_, smacc2::ISmaccComponent::getLogger(), pathInfos_, and pathStack_.

Referenced by clearPath(), cl_nav2z::CbUndoPathBackwards::onEntry(), cl_nav2z::CbUndoPathBackwards::onExit(), popPath(), and pushPath().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onInitialize()

void cl_nav2z::odom_tracker::CpOdomTracker::onInitialize ( )
overrideprotectedvirtual

Reimplemented from smacc2::ISmaccComponent.

Definition at line 57 of file cp_odom_tracker.cpp.

58{
59 // default values
60 recordPointDistanceThreshold_ = 0.005; // 5 mm
61 recordAngularDistanceThreshold_ = 0.1; // radians
62 clearPointDistanceThreshold_ = 0.05; // 5 cm
64
65 auto nh = getNode();
66 RCLCPP_WARN(getLogger(), "[CpOdomTracker] Initializing Odometry Tracker");
67
68 parameterDeclareAndtryGetOrSet(nh, "odom_frame", this->odomFrame_);
70 nh, "record_point_distance_threshold", recordPointDistanceThreshold_);
72 nh, "record_angular_distance_threshold", recordAngularDistanceThreshold_);
74 nh, "clear_point_distance_threshold", clearPointDistanceThreshold_);
76 nh, "clear_angular_distance_threshold", clearAngularDistanceThreshold_);
77
79 {
80 RCLCPP_INFO_STREAM(
81 nh->get_logger(), "[CpOdomTracker] subscribing to odom topic: " << odomTopicName_);
82
83 rclcpp::SensorDataQoS qos;
84 odomSub_ = nh->create_subscription<nav_msgs::msg::Odometry>(
85 odomTopicName_, qos,
86 std::bind(&CpOdomTracker::processOdometryMessage, this, std::placeholders::_1));
87 }
88
90 nh->create_publisher<nav_msgs::msg::Path>("odom_tracker_path", rclcpp::QoS(1));
92 nh->create_publisher<nav_msgs::msg::Path>("odom_tracker_stacked_path", rclcpp::QoS(1));
93}
rclcpp::Subscription< nav_msgs::msg::Odometry >::SharedPtr odomSub_
virtual void processOdometryMessage(const nav_msgs::msg::Odometry::SharedPtr 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.
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr robotBasePathStackedPub_
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr robotBasePathPub_
void parameterDeclareAndtryGetOrSet(rclcpp::Node::SharedPtr &node, std::string param_name, T &value)

References clearAngularDistanceThreshold_, clearPointDistanceThreshold_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), odomFrame_, odomSub_, odomTopicName_, cl_nav2z::odom_tracker::parameterDeclareAndtryGetOrSet(), processOdometryMessage(), recordAngularDistanceThreshold_, recordPointDistanceThreshold_, robotBasePathPub_, robotBasePathStackedPub_, and subscribeToOdometryTopic_.

Here is the call graph for this function:

◆ popPath()

void cl_nav2z::odom_tracker::CpOdomTracker::popPath ( int  pathCount = 1,
bool  keepPreviousPath = false 
)

Definition at line 177 of file cp_odom_tracker.cpp.

178{
179 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex acquire");
180 std::lock_guard<std::mutex> lock(m_mutex_);
181
182 RCLCPP_INFO(getLogger(), "POP PATH ENTRY");
183 this->logStateString();
184
185 if (!keepPreviousPath)
186 {
187 baseTrajectory_.poses.clear();
188 }
189
190 while (popCount > 0 && !pathStack_.empty())
191 {
192 auto & stackedPath = pathStack_.back().poses;
193 auto & stackedPathInfo = pathInfos_.back();
194
195 baseTrajectory_.poses.insert(
196 baseTrajectory_.poses.begin(), stackedPath.begin(), stackedPath.end());
197 this->currentMotionGoal_ = stackedPathInfo.goalPose;
198 pathStack_.pop_back();
199 pathInfos_.pop_back();
200 popCount--;
201
202 RCLCPP_INFO(getLogger(), "POP PATH Iteration ");
203 this->logStateString();
204 }
205
206 RCLCPP_INFO(getLogger(), "POP PATH EXITING");
207 this->logStateString();
208 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex release");
210
211 this->currentMotionGoal_.reset();
212}

References baseTrajectory_, currentMotionGoal_, smacc2::ISmaccComponent::getLogger(), logStateString(), m_mutex_, pathInfos_, pathStack_, and updateAggregatedStackPath().

Referenced by cl_nav2z::CbUndoPathBackwards::onExit().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ processOdometryMessage()

void cl_nav2z::odom_tracker::CpOdomTracker::processOdometryMessage ( const nav_msgs::msg::Odometry::SharedPtr  odom)
virtual

odom callback: Updates the path - this must be called periodically for each odometry message.

processOdometryMessage()

Definition at line 516 of file cp_odom_tracker.cpp.

517{
518 RCLCPP_INFO_THROTTLE(
519 getLogger(), *getNode()->get_clock(), 5000,
520 "[odom_tracker] processing odom msg update heartbeat");
521 std::lock_guard<std::mutex> lock(m_mutex_);
522
524
526 {
527 updateRecordPath(*odom);
528 }
530 {
531 updateClearPath(*odom);
532 }
533
534 // RCLCPP_WARN(getLogger(),"odomTracker odometry callback");
535 if (publishMessages)
536 {
537 rtPublishPaths(odom->header.stamp);
538 }
539
540 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex release");
541}
virtual bool updateRecordPath(const nav_msgs::msg::Odometry &odom)
virtual bool updateClearPath(const nav_msgs::msg::Odometry &odom)

References cl_nav2z::odom_tracker::CLEAR_PATH, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), m_mutex_, publishMessages, cl_nav2z::odom_tracker::RECORD_PATH, rtPublishPaths(), updateClearPath(), updateConfiguration(), updateRecordPath(), and workingMode_.

Referenced by onInitialize().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ pushPath() [1/2]

void cl_nav2z::odom_tracker::CpOdomTracker::pushPath ( )

Definition at line 147 of file cp_odom_tracker.cpp.

147{ this->pushPath(std::string()); }

References pushPath().

Referenced by cl_nav2z::CbNavigateForward::onEntry(), and pushPath().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ pushPath() [2/2]

void cl_nav2z::odom_tracker::CpOdomTracker::pushPath ( std::string  pathname)

Definition at line 149 of file cp_odom_tracker.cpp.

150{
151 RCLCPP_INFO(getLogger(), "odom_tracker m_mutex acquire");
152 std::lock_guard<std::mutex> lock(m_mutex_);
153 this->logStateString(false);
154
156 pathStack_.push_back(baseTrajectory_);
157
158 geometry_msgs::msg::PoseStamped goalPose;
159 if (this->currentMotionGoal_) goalPose = *this->currentMotionGoal_;
160
161 RCLCPP_INFO_STREAM(
162 getLogger(), "[CpOdomTracker] currentPathName: " << pathname
163 << " size: " << baseTrajectory_.poses.size()
164 << " current motion goal: " << goalPose);
165
166 currentPathName_ = pathname;
167
168 // clean the current trajectory to start a new one
169 baseTrajectory_.poses.clear();
170
171 this->logStateString(false);
173
174 this->currentMotionGoal_.reset();
175}

References baseTrajectory_, currentMotionGoal_, currentPathName_, smacc2::ISmaccComponent::getLogger(), logStateString(), m_mutex_, pathInfos_, pathStack_, and updateAggregatedStackPath().

Here is the call graph for this function:

◆ rtPublishPaths()

void cl_nav2z::odom_tracker::CpOdomTracker::rtPublishPaths ( rclcpp::Time  timestamp)
protectedvirtual

rtPublishPaths()

Definition at line 323 of file cp_odom_tracker.cpp.

324{
325 baseTrajectory_.header.stamp = timestamp;
327
328 aggregatedStackPathMsg_.header.stamp = timestamp;
330}

References aggregatedStackPathMsg_, baseTrajectory_, robotBasePathPub_, and robotBasePathStackedPub_.

Referenced by clearPath(), and processOdometryMessage().

Here is the caller graph for this function:

◆ setCurrentMotionGoal()

void cl_nav2z::odom_tracker::CpOdomTracker::setCurrentMotionGoal ( const geometry_msgs::msg::PoseStamped &  pose)

Definition at line 300 of file cp_odom_tracker.cpp.

301{
302 std::lock_guard<std::mutex> lock(m_mutex_);
303 this->currentMotionGoal_ = pose;
304}

References currentMotionGoal_, and m_mutex_.

Referenced by cl_nav2z::CbNavigateForward::onEntry().

Here is the caller graph for this function:

◆ setCurrentPathName()

void cl_nav2z::odom_tracker::CpOdomTracker::setCurrentPathName ( const std::string &  currentPathName)

Definition at line 260 of file cp_odom_tracker.cpp.

261{
262 currentPathName_ = currentPathName;
263}

References currentPathName_.

◆ setPublishMessages()

void cl_nav2z::odom_tracker::CpOdomTracker::setPublishMessages ( bool  value)

setPublishMessages()

Definition at line 138 of file cp_odom_tracker.cpp.

139{
140 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex acquire");
141 std::lock_guard<std::mutex> lock(m_mutex_);
142 publishMessages = value;
143 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex release");
145}

References m_mutex_, publishMessages, and updateAggregatedStackPath().

Here is the call graph for this function:

◆ setStartPoint() [1/2]

void cl_nav2z::odom_tracker::CpOdomTracker::setStartPoint ( const geometry_msgs::msg::Pose &  pose)

Definition at line 280 of file cp_odom_tracker.cpp.

281{
282 std::lock_guard<std::mutex> lock(m_mutex_);
283 RCLCPP_INFO_STREAM(getLogger(), "[CpOdomTracker] set current path starting point: " << pose);
284 geometry_msgs::msg::PoseStamped posestamped;
285 posestamped.header.frame_id = this->odomFrame_;
286 posestamped.header.stamp = getNode()->now();
287 posestamped.pose = pose;
288
289 if (baseTrajectory_.poses.size() > 0)
290 {
291 baseTrajectory_.poses[0] = posestamped;
292 }
293 else
294 {
295 baseTrajectory_.poses.push_back(posestamped);
296 }
298}

References baseTrajectory_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), m_mutex_, odomFrame_, and updateAggregatedStackPath().

Here is the call graph for this function:

◆ setStartPoint() [2/2]

void cl_nav2z::odom_tracker::CpOdomTracker::setStartPoint ( const geometry_msgs::msg::PoseStamped &  pose)

Definition at line 265 of file cp_odom_tracker.cpp.

266{
267 std::lock_guard<std::mutex> lock(m_mutex_);
268 RCLCPP_INFO_STREAM(getLogger(), "[CpOdomTracker] set current path starting point: " << pose);
269 if (baseTrajectory_.poses.size() > 0)
270 {
271 baseTrajectory_.poses[0] = pose;
272 }
273 else
274 {
275 baseTrajectory_.poses.push_back(pose);
276 }
278}

References baseTrajectory_, smacc2::ISmaccComponent::getLogger(), m_mutex_, and updateAggregatedStackPath().

Referenced by cl_nav2z::CbNavigateBackwards::onEntry(), and cl_nav2z::CbNavigateForward::onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setWorkingMode()

void cl_nav2z::odom_tracker::CpOdomTracker::setWorkingMode ( WorkingMode  workingMode)

setWorkingMode()

Definition at line 100 of file cp_odom_tracker.cpp.

101{
102 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex acquire");
103 std::lock_guard<std::mutex> lock(m_mutex_);
104
105 switch (workingMode)
106 {
108 RCLCPP_INFO_STREAM(
109 getLogger(),
110 "[CpOdomTracker] setting working mode to RECORD - record_point_distance_threshold: "
112 << ", record_angular_distance_threshold: " << recordAngularDistanceThreshold_);
113 break;
115 RCLCPP_INFO_STREAM(
116 getLogger(),
117 "[CpOdomTracker] setting working mode to CLEAR - clear_point_distance_threshold: "
119 << ", clear_angular_distance_threshold: " << clearAngularDistanceThreshold_);
120 break;
122 RCLCPP_INFO_STREAM(getLogger(), "[CpOdomTracker] setting working mode to IDLE");
123 break;
124 default:
125
126 RCLCPP_INFO_STREAM(getLogger(), "[CpOdomTracker] setting working mode to <UNKNOWN>");
127 }
128
129 workingMode_ = workingMode;
130 // RCLCPP_INFO(getLogger(),"odom_tracker m_mutex release");
131}

References cl_nav2z::odom_tracker::CLEAR_PATH, clearAngularDistanceThreshold_, clearPointDistanceThreshold_, smacc2::ISmaccComponent::getLogger(), cl_nav2z::odom_tracker::IDLE, m_mutex_, cl_nav2z::odom_tracker::RECORD_PATH, recordAngularDistanceThreshold_, recordPointDistanceThreshold_, and workingMode_.

Referenced by cl_nav2z::CbNavigateBackwards::onEntry(), cl_nav2z::CbNavigateForward::onEntry(), cl_nav2z::CbUndoPathBackwards::onEntry(), cl_nav2z::CbNavigateBackwards::onExit(), and cl_nav2z::CbNavigateForward::onExit().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ updateAggregatedStackPath()

void cl_nav2z::odom_tracker::CpOdomTracker::updateAggregatedStackPath ( )
protected

Definition at line 332 of file cp_odom_tracker.cpp.

333{
334 aggregatedStackPathMsg_.poses.clear();
335 for (auto & p : pathStack_)
336 {
337 aggregatedStackPathMsg_.poses.insert(
338 aggregatedStackPathMsg_.poses.end(), p.poses.begin(), p.poses.end());
339 }
340
341 aggregatedStackPathMsg_.header.frame_id = this->odomFrame_;
342}

References aggregatedStackPathMsg_, odomFrame_, and pathStack_.

Referenced by clearPath(), popPath(), pushPath(), setPublishMessages(), setStartPoint(), and setStartPoint().

Here is the caller graph for this function:

◆ updateClearPath()

bool cl_nav2z::odom_tracker::CpOdomTracker::updateClearPath ( const nav_msgs::msg::Odometry &  odom)
protectedvirtual

updateBackward()

Track robot base pose

Not removing point because it is enough far from the last cord point

Definition at line 349 of file cp_odom_tracker.cpp.

350{
351 // we initially accept any message if the queue is empty
353 geometry_msgs::msg::PoseStamped base_pose;
354
355 base_pose.pose = odom.pose.pose;
356 base_pose.header = odom.header;
357 baseTrajectory_.header = odom.header;
358
359 bool acceptBackward = false;
360 bool clearingError = false;
361 bool finished = false;
362
363 while (!finished)
364 {
365 if (
366 baseTrajectory_.poses.size() <=
367 1) // we at least keep always the first point of the forward path when clearing
368 // (this is important for backwards planner replanning and not losing the
369 // last goal)
370 {
371 acceptBackward = false;
372 finished = true;
373 }
374 else
375 {
376 auto & carrotPose = baseTrajectory_.poses.back().pose;
377 auto & carrotPoint = carrotPose.position;
378
379 double carrotAngle = tf2::getYaw(carrotPose.orientation);
380
381 auto & currePose = base_pose.pose;
382 auto & currePoint = currePose.position;
383 double currentAngle = tf2::getYaw(currePose.orientation);
384
385 double lastpointdist = p2pDistance(carrotPoint, currePoint);
386 double goalAngleOffset = fabs(angles::shortest_angular_distance(carrotAngle, currentAngle));
387
388 acceptBackward = !baseTrajectory_.poses.empty() &&
389 lastpointdist < clearPointDistanceThreshold_ &&
390 goalAngleOffset < clearAngularDistanceThreshold_;
391
392 clearingError = lastpointdist > 2 * clearPointDistanceThreshold_;
393 RCLCPP_DEBUG_STREAM(
394 getLogger(), "[CpOdomTracker] clearing (accepted: " << acceptBackward
395 << ") linerr: " << lastpointdist
396 << ", anglerr: " << goalAngleOffset);
397 }
398
399 // RCLCPP_INFO(getLogger(),"Backwards, last distance: %lf < %lf accept: %d", dist,
400 // minPointDistanceBackwardThresh_, acceptBackward);
401 if (
402 acceptBackward &&
403 baseTrajectory_.poses.size() > 1) /* we always leave at least one item, specially interesting
404 for the backward local planner reach
405 the backwards goal with enough precision*/
406 {
407 baseTrajectory_.poses.pop_back();
408 }
409 else if (clearingError)
410 {
411 finished = true;
412 RCLCPP_WARN(getLogger(), "[CpOdomTracker] Incorrect odom clearing motion.");
413 }
414 else
415 {
416 finished = true;
418 }
419 }
420
421 return acceptBackward;
422}
double p2pDistance(const geometry_msgs::msg::Point &p1, const geometry_msgs::msg::Point &p2)

References baseTrajectory_, clearAngularDistanceThreshold_, clearPointDistanceThreshold_, smacc2::ISmaccComponent::getLogger(), and cl_nav2z::odom_tracker::p2pDistance().

Referenced by processOdometryMessage().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ updateConfiguration()

void cl_nav2z::odom_tracker::CpOdomTracker::updateConfiguration ( )
protected

reconfigCB()

Definition at line 487 of file cp_odom_tracker.cpp.

488{
489 if (!getNode()->get_parameter("odom_frame", this->odomFrame_))
490 {
491 }
492
493 if (!getNode()->get_parameter("record_point_distance_threshold", recordPointDistanceThreshold_))
494 {
495 }
496
497 if (!getNode()->get_parameter(
498 "record_angular_distance_threshold", recordAngularDistanceThreshold_))
499 {
500 }
501
502 if (!getNode()->get_parameter("clear_point_distance_threshold", clearPointDistanceThreshold_))
503 {
504 }
505
506 if (!getNode()->get_parameter("clear_angular_distance_threshold", clearAngularDistanceThreshold_))
507 {
508 }
509}

References clearAngularDistanceThreshold_, clearPointDistanceThreshold_, smacc2::ISmaccComponent::getNode(), odomFrame_, recordAngularDistanceThreshold_, and recordPointDistanceThreshold_.

Referenced by processOdometryMessage().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ updateRecordPath()

bool cl_nav2z::odom_tracker::CpOdomTracker::updateRecordPath ( const nav_msgs::msg::Odometry &  odom)
protectedvirtual

updateRecordPath()

Track robot base pose

Definition at line 428 of file cp_odom_tracker.cpp.

429{
431 geometry_msgs::msg::PoseStamped base_pose;
432
433 base_pose.pose = odom.pose.pose;
434 base_pose.header = odom.header;
435 baseTrajectory_.header = odom.header;
436
437 bool enqueueOdomMessage = false;
438
439 double dist = -1;
440 if (baseTrajectory_.poses.empty())
441 {
442 enqueueOdomMessage = true;
443 }
444 else
445 {
446 const auto & prevPose = baseTrajectory_.poses.back().pose;
447 const geometry_msgs::msg::Point & prevPoint = prevPose.position;
448 double prevAngle = tf2::getYaw(prevPose.orientation);
449
450 const geometry_msgs::msg::Point & currePoint = base_pose.pose.position;
451 double currentAngle = tf2::getYaw(base_pose.pose.orientation);
452
453 dist = p2pDistance(prevPoint, currePoint);
454 double goalAngleOffset = fabs(angles::shortest_angular_distance(prevAngle, currentAngle));
455
456 // RCLCPP_WARN(getLogger(),"dist %lf vs min %lf", dist, recordPointDistanceThreshold_);
457
458 RCLCPP_WARN_THROTTLE(getLogger(), *getNode()->get_clock(), 2000, "odom received");
459
461 {
462 enqueueOdomMessage = true;
463 }
464 else
465 {
466 // RCLCPP_WARN(getLogger(),"skip odom, dist: %lf", dist);
467 enqueueOdomMessage = false;
468 }
469 }
470
471 if (enqueueOdomMessage)
472 {
473 RCLCPP_WARN_THROTTLE(
474 getLogger(), *getNode()->get_clock(), 2000, "enqueue odom tracker pose. dist %lf vs min %lf",
476 baseTrajectory_.poses.push_back(base_pose);
477 }
478
479 return enqueueOdomMessage;
480}

References baseTrajectory_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), cl_nav2z::odom_tracker::p2pDistance(), recordAngularDistanceThreshold_, and recordPointDistanceThreshold_.

Referenced by processOdometryMessage().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ aggregatedStackPathMsg_

nav_msgs::msg::Path cl_nav2z::odom_tracker::CpOdomTracker::aggregatedStackPathMsg_
protected

Definition at line 163 of file cp_odom_tracker.hpp.

Referenced by rtPublishPaths(), and updateAggregatedStackPath().

◆ baseTrajectory_

nav_msgs::msg::Path cl_nav2z::odom_tracker::CpOdomTracker::baseTrajectory_
protected

Processed path for the mouth of the reel.

Definition at line 149 of file cp_odom_tracker.hpp.

Referenced by clearPath(), getPath(), logStateString(), popPath(), pushPath(), rtPublishPaths(), setStartPoint(), setStartPoint(), updateClearPath(), and updateRecordPath().

◆ clearAngularDistanceThreshold_

double cl_nav2z::odom_tracker::CpOdomTracker::clearAngularDistanceThreshold_
protected

rads

Definition at line 138 of file cp_odom_tracker.hpp.

Referenced by onInitialize(), setWorkingMode(), updateClearPath(), and updateConfiguration().

◆ clearPointDistanceThreshold_

double cl_nav2z::odom_tracker::CpOdomTracker::clearPointDistanceThreshold_
protected

rads

Definition at line 135 of file cp_odom_tracker.hpp.

Referenced by onInitialize(), setWorkingMode(), updateClearPath(), and updateConfiguration().

◆ currentMotionGoal_

std::optional<geometry_msgs::msg::PoseStamped> cl_nav2z::odom_tracker::CpOdomTracker::currentMotionGoal_
protected

◆ currentPathName_

std::string cl_nav2z::odom_tracker::CpOdomTracker::currentPathName_
protected

Definition at line 169 of file cp_odom_tracker.hpp.

Referenced by logStateString(), pushPath(), and setCurrentPathName().

◆ m_mutex_

std::mutex cl_nav2z::odom_tracker::CpOdomTracker::m_mutex_
protected

◆ odomFrame_

std::string cl_nav2z::odom_tracker::CpOdomTracker::odomFrame_
protected

◆ odomSub_

rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr cl_nav2z::odom_tracker::CpOdomTracker::odomSub_
protected

Definition at line 125 of file cp_odom_tracker.hpp.

Referenced by onInitialize().

◆ odomTopicName_

std::string cl_nav2z::odom_tracker::CpOdomTracker::odomTopicName_
protected

Definition at line 142 of file cp_odom_tracker.hpp.

Referenced by CpOdomTracker(), and onInitialize().

◆ pathInfos_

std::vector<PathInfo> cl_nav2z::odom_tracker::CpOdomTracker::pathInfos_
protected

Definition at line 161 of file cp_odom_tracker.hpp.

Referenced by logStateString(), popPath(), and pushPath().

◆ pathStack_

std::vector<nav_msgs::msg::Path> cl_nav2z::odom_tracker::CpOdomTracker::pathStack_
protected

Definition at line 153 of file cp_odom_tracker.hpp.

Referenced by logStateString(), popPath(), pushPath(), and updateAggregatedStackPath().

◆ publishMessages

bool cl_nav2z::odom_tracker::CpOdomTracker::publishMessages
protected

Definition at line 146 of file cp_odom_tracker.hpp.

Referenced by CpOdomTracker(), processOdometryMessage(), and setPublishMessages().

◆ recordAngularDistanceThreshold_

double cl_nav2z::odom_tracker::CpOdomTracker::recordAngularDistanceThreshold_
protected

Meters.

Definition at line 132 of file cp_odom_tracker.hpp.

Referenced by onInitialize(), setWorkingMode(), updateConfiguration(), and updateRecordPath().

◆ recordPointDistanceThreshold_

double cl_nav2z::odom_tracker::CpOdomTracker::recordPointDistanceThreshold_
protected

How much distance there is between two points of the path.

Definition at line 129 of file cp_odom_tracker.hpp.

Referenced by onInitialize(), setWorkingMode(), updateConfiguration(), and updateRecordPath().

◆ robotBasePathPub_

rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr cl_nav2z::odom_tracker::CpOdomTracker::robotBasePathPub_
protected

Definition at line 119 of file cp_odom_tracker.hpp.

Referenced by onInitialize(), and rtPublishPaths().

◆ robotBasePathStackedPub_

rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr cl_nav2z::odom_tracker::CpOdomTracker::robotBasePathStackedPub_
protected

Definition at line 120 of file cp_odom_tracker.hpp.

Referenced by onInitialize(), and rtPublishPaths().

◆ subscribeToOdometryTopic_

bool cl_nav2z::odom_tracker::CpOdomTracker::subscribeToOdometryTopic_
protected

Definition at line 166 of file cp_odom_tracker.hpp.

Referenced by CpOdomTracker(), and onInitialize().

◆ workingMode_

WorkingMode cl_nav2z::odom_tracker::CpOdomTracker::workingMode_
protected

Definition at line 151 of file cp_odom_tracker.hpp.

Referenced by CpOdomTracker(), processOdometryMessage(), and setWorkingMode().


The documentation for this class was generated from the following files: