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");
80 nh->get_logger(),
"[OdomTracker] subscribing to odom topic: " <<
odomTopicName_);
82 rclcpp::SensorDataQoS qos;
83 odomSub_ = nh->create_subscription<nav_msgs::msg::Odometry>(
88 robotBasePathPub_ = nh->create_publisher<nav_msgs::msg::Path>(
"odom_tracker_path", 1);
90 nh->create_publisher<nav_msgs::msg::Path>(
"odom_tracker_stacked_path", 1);
101 std::lock_guard<std::mutex> lock(
m_mutex_);
108 "[OdomTracker] setting working mode to RECORD - record_point_distance_threshold: "
115 "[OdomTracker] setting working mode to CLEAR - clear_point_distance_threshold: "
120 RCLCPP_INFO_STREAM(
getLogger(),
"[OdomTracker] setting working mode to IDLE");
124 RCLCPP_INFO_STREAM(
getLogger(),
"[OdomTracker] setting working mode to <UNKNOWN>");
139 std::lock_guard<std::mutex> lock(
m_mutex_);
149 RCLCPP_INFO(
getLogger(),
"odom_tracker m_mutex acquire");
150 std::lock_guard<std::mutex> lock(
m_mutex_);
156 geometry_msgs::msg::PoseStamped goalPose;
160 getLogger(),
"[OdomTracker] currentPathName: " << pathname
162 <<
" current motion goal: " << goalPose);
177 RCLCPP_INFO(
getLogger(),
"odom_tracker m_mutex acquire");
178 std::lock_guard<std::mutex> lock(
m_mutex_);
180 RCLCPP_INFO(
getLogger(),
"POP PATH ENTRY");
183 if (!keepPreviousPath)
194 baseTrajectory_.poses.begin(), stackedPath.begin(), stackedPath.end());
200 RCLCPP_INFO(
getLogger(),
"POP PATH Iteration ");
204 RCLCPP_INFO(
getLogger(),
"POP PATH EXITING");
206 RCLCPP_INFO(
getLogger(),
"odom_tracker m_mutex release");
214 std::stringstream ss;
215 ss <<
"--- odom tracker state ---" << std::endl;
221 ss <<
" - [STACK-HEAD active path size: " <<
baseTrajectory_.poses.size() <<
"]" << std::endl;
223 for (
auto & p :
pathStack_ | boost::adaptors::reversed)
226 std::string goalstr =
"[]";
227 if (pathinfo.goalPose)
229 std::stringstream ss;
230 ss << *(pathinfo.goalPose);
234 ss <<
" - p " << i <<
"[" << p.header.stamp <<
"], size: " << p.poses.size() <<
" - "
235 << pathinfo.name <<
" - goal: " << goalstr << std::endl;
241 RCLCPP_DEBUG(
getLogger(), ss.str().c_str());
243 RCLCPP_INFO(
getLogger(), ss.str().c_str());
248 std::lock_guard<std::mutex> lock(
m_mutex_);
265 std::lock_guard<std::mutex> lock(
m_mutex_);
266 RCLCPP_INFO_STREAM(
getLogger(),
"[OdomTracker] set current path starting point: " << pose);
280 std::lock_guard<std::mutex> lock(
m_mutex_);
281 RCLCPP_INFO_STREAM(
getLogger(),
"[OdomTracker] set current path starting point: " << pose);
282 geometry_msgs::msg::PoseStamped posestamped;
283 posestamped.header.frame_id = this->
odomFrame_;
284 posestamped.header.stamp =
getNode()->now();
285 posestamped.pose = pose;
300 std::lock_guard<std::mutex> lock(
m_mutex_);
306 std::lock_guard<std::mutex> lock(
m_mutex_);
312 std::lock_guard<std::mutex> lock(
m_mutex_);
351 geometry_msgs::msg::PoseStamped base_pose;
353 base_pose.pose = odom.pose.pose;
354 base_pose.header = odom.header;
357 bool acceptBackward =
false;
358 bool clearingError =
false;
359 bool finished =
false;
369 acceptBackward =
false;
375 auto & carrotPoint = carrotPose.position;
377 double carrotAngle = tf2::getYaw(carrotPose.orientation);
379 auto & currePose = base_pose.pose;
380 auto & currePoint = currePose.position;
381 double currentAngle = tf2::getYaw(currePose.orientation);
383 double lastpointdist =
p2pDistance(carrotPoint, currePoint);
384 double goalAngleOffset = fabs(angles::shortest_angular_distance(carrotAngle, currentAngle));
392 getLogger(),
"[OdomTracker] clearing (accepted: " << acceptBackward
393 <<
") linerr: " << lastpointdist
394 <<
", anglerr: " << goalAngleOffset);
407 else if (clearingError)
410 RCLCPP_WARN(
getLogger(),
"[OdomTracker] Incorrect odom clearing motion.");
419 return acceptBackward;
429 geometry_msgs::msg::PoseStamped base_pose;
431 base_pose.pose = odom.pose.pose;
432 base_pose.header = odom.header;
435 bool enqueueOdomMessage =
false;
440 enqueueOdomMessage =
true;
445 const geometry_msgs::msg::Point & prevPoint = prevPose.position;
446 double prevAngle = tf2::getYaw(prevPose.orientation);
448 const geometry_msgs::msg::Point & currePoint = base_pose.pose.position;
449 double currentAngle = tf2::getYaw(base_pose.pose.orientation);
452 double goalAngleOffset = fabs(angles::shortest_angular_distance(prevAngle, currentAngle));
456 RCLCPP_WARN_THROTTLE(
getLogger(), *
getNode()->get_clock(), 2000,
"odom received");
460 enqueueOdomMessage =
true;
465 enqueueOdomMessage =
false;
469 if (enqueueOdomMessage)
471 RCLCPP_WARN_THROTTLE(
472 getLogger(), *
getNode()->get_clock(), 2000,
"enqueue odom tracker pose. dist %lf vs min %lf",
477 return enqueueOdomMessage;
516 RCLCPP_INFO_THROTTLE(
getLogger(), *
getNode()->get_clock(), 2000,
"[odom_tracker] update");
517 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 logStateString(bool debug=true)
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() 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)