22#include <angles/angles.h>
26#include <boost/range/adaptor/reversed.hpp>
43 rclcpp::Node::SharedPtr & node, std::string param_name,
T & value)
45 if (!node->get_parameter(param_name, value))
47 RCLCPP_INFO_STREAM(node->get_logger(),
"[OdomTracker] autoset " << param_name <<
": " << value);
48 node->declare_parameter(param_name, value);
52 RCLCPP_INFO_STREAM(node->get_logger(),
"[OdomTracker] " << param_name <<
": " << value);
65 RCLCPP_WARN(
getLogger(),
"[OdomTracker] Initializing Odometry Tracker");
79 rclcpp::SensorDataQoS qos;
80 odomSub_ = nh->create_subscription<nav_msgs::msg::Odometry>(
85 robotBasePathPub_ = nh->create_publisher<nav_msgs::msg::Path>(
"odom_tracker_path", 1);
87 nh->create_publisher<nav_msgs::msg::Path>(
"odom_tracker_stacked_path", 1);
98 std::lock_guard<std::mutex> lock(
m_mutex_);
105 "[OdomTracker] setting working mode to RECORD - record_point_distance_threshold: "
112 "[OdomTracker] setting working mode to CLEAR - clear_point_distance_threshold: "
117 RCLCPP_INFO_STREAM(
getLogger(),
"[OdomTracker] setting working mode to IDLE");
121 RCLCPP_INFO_STREAM(
getLogger(),
"[OdomTracker] setting working mode to <UNKNOWN>");
136 std::lock_guard<std::mutex> lock(
m_mutex_);
146 RCLCPP_INFO(
getLogger(),
"odom_tracker m_mutex acquire");
147 std::lock_guard<std::mutex> lock(
m_mutex_);
148 RCLCPP_INFO(
getLogger(),
"PUSH_PATH PATH EXITTING");
159 RCLCPP_INFO(
getLogger(),
"PUSH_PATH PATH EXITTING");
161 RCLCPP_INFO(
getLogger(),
"odom_tracker m_mutex release");
169 RCLCPP_INFO(
getLogger(),
"odom_tracker m_mutex acquire");
170 std::lock_guard<std::mutex> lock(
m_mutex_);
172 RCLCPP_INFO(
getLogger(),
"POP PATH ENTRY");
175 if (!keepPreviousPath)
186 baseTrajectory_.poses.begin(), stackedPath.begin(), stackedPath.end());
192 RCLCPP_INFO(
getLogger(),
"POP PATH Iteration ");
196 RCLCPP_INFO(
getLogger(),
"POP PATH EXITING");
198 RCLCPP_INFO(
getLogger(),
"odom_tracker m_mutex release");
206 std::stringstream ss;
207 ss <<
"--- odom tracker state ---" << std::endl;
213 ss <<
" - [STACK-HEAD active path size: " <<
baseTrajectory_.poses.size() <<
"]" << std::endl;
215 for (
auto & p :
pathStack_ | boost::adaptors::reversed)
218 std::string goalstr =
"[]";
219 if (pathinfo.goalPose)
221 std::stringstream ss;
222 ss << *(pathinfo.goalPose);
226 ss <<
" - p " << i <<
"[" << p.header.stamp <<
"], size: " << p.poses.size() <<
" - "
227 << pathinfo.name <<
" - goal: " << goalstr << std::endl;
231 RCLCPP_INFO(
getLogger(), ss.str().c_str());
236 std::lock_guard<std::mutex> lock(
m_mutex_);
253 std::lock_guard<std::mutex> lock(
m_mutex_);
254 RCLCPP_INFO_STREAM(
getLogger(),
"[OdomTracker] set current path starting point: " << pose);
268 std::lock_guard<std::mutex> lock(
m_mutex_);
269 RCLCPP_INFO_STREAM(
getLogger(),
"[OdomTracker] set current path starting point: " << pose);
270 geometry_msgs::msg::PoseStamped posestamped;
271 posestamped.header.frame_id = this->
odomFrame_;
272 posestamped.header.stamp =
getNode()->now();
273 posestamped.pose = pose;
288 std::lock_guard<std::mutex> lock(
m_mutex_);
294 std::lock_guard<std::mutex> lock(
m_mutex_);
300 std::lock_guard<std::mutex> lock(
m_mutex_);
339 geometry_msgs::msg::PoseStamped base_pose;
341 base_pose.pose = odom.pose.pose;
342 base_pose.header = odom.header;
345 bool acceptBackward =
false;
346 bool clearingError =
false;
347 bool finished =
false;
357 acceptBackward =
false;
363 auto & carrotPoint = carrotPose.position;
365 double carrotAngle = tf2::getYaw(carrotPose.orientation);
367 auto & currePose = base_pose.pose;
368 auto & currePoint = currePose.position;
369 double currentAngle = tf2::getYaw(currePose.orientation);
371 double lastpointdist =
p2pDistance(carrotPoint, currePoint);
372 double goalAngleOffset = fabs(angles::shortest_angular_distance(carrotAngle, currentAngle));
380 getLogger(),
"[OdomTracker] clearing (accepted: " << acceptBackward
381 <<
") linerr: " << lastpointdist
382 <<
", anglerr: " << goalAngleOffset);
395 else if (clearingError)
398 RCLCPP_WARN(
getLogger(),
"[OdomTracker] Incorrect odom clearing motion.");
407 return acceptBackward;
417 geometry_msgs::msg::PoseStamped base_pose;
419 base_pose.pose = odom.pose.pose;
420 base_pose.header = odom.header;
423 bool enqueueOdomMessage =
false;
428 enqueueOdomMessage =
true;
433 const geometry_msgs::msg::Point & prevPoint = prevPose.position;
434 double prevAngle = tf2::getYaw(prevPose.orientation);
436 const geometry_msgs::msg::Point & currePoint = base_pose.pose.position;
437 double currentAngle = tf2::getYaw(base_pose.pose.orientation);
440 double goalAngleOffset = fabs(angles::shortest_angular_distance(prevAngle, currentAngle));
446 enqueueOdomMessage =
true;
451 enqueueOdomMessage =
false;
455 if (enqueueOdomMessage)
460 return enqueueOdomMessage;
500 std::lock_guard<std::mutex> lock(
m_mutex_);
void setCurrentPathName(const std::string ¤tPathName)
nav_msgs::msg::Path getPath()
void setCurrentMotionGoal(const geometry_msgs::msg::PoseStamped &pose)
virtual void rtPublishPaths(rclcpp::Time timestamp)
bool subscribeToOdometryTopic_
double recordPointDistanceThreshold_
How much distance there is between two points of the path.
virtual bool updateClearPath(const nav_msgs::msg::Odometry &odom)
std::string currentPathName_
void setPublishMessages(bool value)
double recordAngularDistanceThreshold_
Meters.
double clearPointDistanceThreshold_
rads
void updateConfiguration()
std::optional< geometry_msgs::msg::PoseStamped > currentMotionGoal_
double clearAngularDistanceThreshold_
rads
OdomTracker(std::string odomtopicName="/odom", std::string odomFrame="odom")
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr robotBasePathPub_
nav_msgs::msg::Path baseTrajectory_
Processed path for the mouth of the reel.
void setWorkingMode(WorkingMode workingMode)
std::vector< nav_msgs::msg::Path > pathStack_
void popPath(int pathCount=1, bool keepPreviousPath=false)
void onInitialize() override
std::string odomTopicName_
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 setStartPoint(const geometry_msgs::msg::PoseStamped &pose)
nav_msgs::msg::Path aggregatedStackPathMsg_
rclcpp::Subscription< nav_msgs::msg::Odometry >::SharedPtr odomSub_
rclcpp::Publisher< nav_msgs::msg::Path >::SharedPtr robotBasePathStackedPub_
void updateAggregatedStackPath()
virtual bool updateRecordPath(const nav_msgs::msg::Odometry &odom)
std::optional< geometry_msgs::msg::PoseStamped > getCurrentMotionGoal()
std::vector< PathInfo > pathInfos_
rclcpp::Logger getLogger()
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)