22#include <angles/angles.h>
28#include <boost/range/adaptor/reversed.hpp>
46 rclcpp::Node::SharedPtr & node, std::string param_name, T & value)
48 if (!node->get_parameter(param_name, value))
51 node->get_logger(),
"[CpOdomTracker] autoset " << param_name <<
": " << value);
52 node->declare_parameter(param_name, value);
56 RCLCPP_INFO_STREAM(node->get_logger(),
"[CpOdomTracker] " << param_name <<
": " << value);
69 RCLCPP_WARN(
getLogger(),
"[CpOdomTracker] Initializing Odometry Tracker");
85 nh->create_publisher<nav_msgs::msg::Path>(
"odom_tracker_path", rclcpp::QoS(1));
88 nh->create_publisher<nav_msgs::msg::Path>(
"odom_tracker_stacked_path", rclcpp::QoS(1));
93 nh->get_logger(),
"[CpOdomTracker] subscribing to odom topic: " <<
odomTopicName_);
95 rclcpp::SensorDataQoS qos;
96 odomSub_ = nh->create_subscription<nav_msgs::msg::Odometry>(
109 nh->get_logger(),
"[CpOdomTracker] unknown strategy: " << (
int)this->strategy_);
119 const std::vector<rclcpp::Parameter> & parameters)
121 std::lock_guard<std::mutex> lock(
m_mutex_);
122 RCLCPP_INFO(
getLogger(),
"odom_tracker m_mutex acquire");
124 for (
const auto & param : parameters)
126 if (param.get_name() ==
"record_point_distance_threshold")
130 else if (param.get_name() ==
"record_angular_distance_threshold")
134 else if (param.get_name() ==
"clear_point_distance_threshold")
138 else if (param.get_name() ==
"clear_angular_distance_threshold")
142 else if (param.get_name() ==
"odom_frame")
148 rcl_interfaces::msg::SetParametersResult result;
149 result.successful =
true;
150 result.reason =
"success";
161 std::lock_guard<std::mutex> lock(
m_mutex_);
168 "[CpOdomTracker] setting working mode to RECORD - record_point_distance_threshold: "
175 "[CpOdomTracker] setting working mode to CLEAR - clear_point_distance_threshold: "
180 RCLCPP_INFO_STREAM(
getLogger(),
"[CpOdomTracker] setting working mode to IDLE");
184 RCLCPP_INFO_STREAM(
getLogger(),
"[CpOdomTracker] setting working mode to <UNKNOWN>");
187 if (this->
odomSub_ !=
nullptr && this->
odomSub_->get_publisher_count() == 0)
191 "[CpOdomTracker] Odom tracker cannot record the path because there is no publisher to the "
207 std::lock_guard<std::mutex> lock(
m_mutex_);
217 RCLCPP_INFO(
getLogger(),
"odom_tracker m_mutex acquire, to push path");
218 std::lock_guard<std::mutex> lock(
m_mutex_);
221 if (this->
odomSub_ !=
nullptr && this->
odomSub_->get_publisher_count() == 0)
225 "[CpOdomTracker] Odom tracker cannot record the path because there is no publisher to the "
232 geometry_msgs::msg::PoseStamped goalPose;
236 getLogger(),
"[CpOdomTracker] currentPathName: " << pathname
238 <<
" current motion goal: " << goalPose);
253 RCLCPP_INFO(
getLogger(),
"odom_tracker m_mutex acquire to pop path");
254 std::lock_guard<std::mutex> lock(
m_mutex_);
256 RCLCPP_INFO(
getLogger(),
"POP PATH ENTRY");
259 if (this->
odomSub_ !=
nullptr && this->
odomSub_->get_publisher_count() == 0)
263 "[CpOdomTracker] Odom tracker cannot record the path because there is no publisher to the "
267 if (!keepPreviousPath)
278 baseTrajectory_.poses.begin(), stackedPath.begin(), stackedPath.end());
284 RCLCPP_INFO(
getLogger(),
"POP PATH Iteration ");
288 RCLCPP_INFO(
getLogger(),
"POP PATH EXITING");
290 RCLCPP_INFO(
getLogger(),
"odom_tracker m_mutex release");
298 std::stringstream ss;
299 ss <<
"--- odom tracker state ---" << std::endl;
305 ss <<
" - [STACK-HEAD active path size: " <<
baseTrajectory_.poses.size() <<
"]" << std::endl;
307 for (
auto & p :
pathStack_ | boost::adaptors::reversed)
310 std::string goalstr =
"[]";
311 if (pathinfo.goalPose)
313 std::stringstream ss;
314 ss << *(pathinfo.goalPose);
318 ss <<
" - p " << i <<
"[" << p.header.stamp <<
"], size: " << p.poses.size() <<
" - "
319 << pathinfo.name <<
" - goal: " << goalstr << std::endl;
324 if (this->
odomSub_ !=
nullptr && this->
odomSub_->get_publisher_count() == 0)
327 <<
"[CpOdomTracker] Odom tracker cannot record the path because there is no publisher to "
333 RCLCPP_DEBUG(
getLogger(), ss.str().c_str());
335 RCLCPP_INFO(
getLogger(), ss.str().c_str());
340 RCLCPP_INFO(
getLogger(),
"odom_tracker m_mutex acquire to clear path");
341 std::lock_guard<std::mutex> lock(
m_mutex_);
353 RCLCPP_INFO_STREAM(
getLogger(),
"[CpOdomTracker] set current path name: " << currentPathName);
359 std::lock_guard<std::mutex> lock(
m_mutex_);
360 RCLCPP_INFO_STREAM(
getLogger(),
"[CpOdomTracker] set current path starting point: " << pose);
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;
394 std::lock_guard<std::mutex> lock(
m_mutex_);
400 std::lock_guard<std::mutex> lock(
m_mutex_);
406 std::lock_guard<std::mutex> lock(
m_mutex_);
447 bool acceptBackward =
false;
448 bool clearingError =
false;
449 bool finished =
false;
459 acceptBackward =
false;
465 auto & carrotPoint = carrotPose.position;
467 double carrotAngle = tf2::getYaw(carrotPose.orientation);
469 auto & currePose = base_pose.pose;
470 auto & currePoint = currePose.position;
471 double currentAngle = tf2::getYaw(currePose.orientation);
473 double lastpointdist =
p2pDistance(carrotPoint, currePoint);
474 double goalAngleOffset = fabs(angles::shortest_angular_distance(carrotAngle, currentAngle));
482 getLogger(),
"[CpOdomTracker] clearing (accepted: " << acceptBackward
483 <<
") linerr: " << lastpointdist
484 <<
", anglerr: " << goalAngleOffset);
497 else if (clearingError)
500 RCLCPP_WARN(
getLogger(),
"[CpOdomTracker] Incorrect odom clearing motion.");
509 return acceptBackward;
522 bool enqueueOdomMessage =
false;
527 enqueueOdomMessage =
true;
532 const geometry_msgs::msg::Point & prevPoint = prevPose.position;
533 double prevAngle = tf2::getYaw(prevPose.orientation);
535 const geometry_msgs::msg::Point & currePoint = base_pose.pose.position;
536 double currentAngle = tf2::getYaw(base_pose.pose.orientation);
539 double goalAngleOffset = fabs(angles::shortest_angular_distance(prevAngle, currentAngle));
543 RCLCPP_WARN_THROTTLE(
getLogger(), *
getNode()->get_clock(), 2000,
"odom received");
547 enqueueOdomMessage =
true;
552 enqueueOdomMessage =
false;
556 if (enqueueOdomMessage)
558 RCLCPP_WARN_THROTTLE(
559 getLogger(), *
getNode()->get_clock(), 2000,
"enqueue odom tracker pose. dist %lf vs min %lf",
564 return enqueueOdomMessage;
605 RCLCPP_INFO(
getLogger(),
"odom_tracker update");
607 RCLCPP_INFO(
getLogger(),
"odom tracker updatd pose, frame: %s", pose.header.frame_id.c_str());
609 RCLCPP_INFO(
getLogger(),
"odom_tracker update end");
619 geometry_msgs::msg::PoseStamped base_pose;
620 base_pose.pose = odom->pose.pose;
621 base_pose.header = odom->header;
633 RCLCPP_INFO_THROTTLE(
635 "[odom_tracker] processing odom msg update heartbeat");
636 std::lock_guard<std::mutex> lock(
m_mutex_);
geometry_msgs::msg::PoseStamped toPoseStampedMsg()
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::string odomTopicName_
std::string currentPathName_
double clearPointDistanceThreshold_
rads
double clearAngularDistanceThreshold_
rads
cl_nav2z::Pose * robotPose_
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 ¤tPathName)
nav_msgs::msg::Path getPath()
virtual void odomMessageCallback(const nav_msgs::msg::Odometry::SharedPtr odom)
std::vector< PathInfo > pathInfos_
double recordAngularDistanceThreshold_
Meters.
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)
nav_msgs::msg::Path aggregatedStackPathMsg_
std::vector< nav_msgs::msg::Path > pathStack_
void setPublishMessages(bool value)
void setWorkingMode(WorkingMode workingMode)
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr robotBasePathPub_
void updateAggregatedStackPath()
rcl_interfaces::msg::SetParametersResult parametersCallback(const std::vector< rclcpp::Parameter > ¶meters)
std::optional< geometry_msgs::msg::PoseStamped > getCurrentMotionGoal()
void onInitialize() override
void setStartPoint(const geometry_msgs::msg::PoseStamped &pose)
void updateConfiguration()
OdomTrackerStrategy strategy_
CpOdomTracker(std::string odomtopicName="/odom", std::string odomFrame="odom", OdomTrackerStrategy strategy=OdomTrackerStrategy::ODOMETRY_SUBSCRIBER)
void logStateString(bool debug=true)
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)