Skip to content
Snippets Groups Projects
Commit 5a6fc036 authored by Steven Macenski's avatar Steven Macenski
Browse files

getFootprint duration overrides

parent c31e15ef
No related branches found
No related tags found
No related merge requests found
......@@ -49,11 +49,16 @@ public:
~FootprintSubscriber() {}
// Returns an oriented robot footprint at current time.
bool getFootprint(
std::vector<geometry_msgs::msg::Point> & footprint,
rclcpp::Duration & valid_footprint_timeout);
bool getFootprint(std::vector<geometry_msgs::msg::Point> & footprint);
// Returns an oriented robot footprint.
// The second parameter is the time the fooptrint was at this orientation.
bool getFootprint(std::vector<geometry_msgs::msg::Point> & footprint, rclcpp::Time & stamp);
bool getFootprint(
std::vector<geometry_msgs::msg::Point> & footprint,
rclcpp::Time & stamp, rclcpp::Duration valid_footprint_timeout);
protected:
// Interfaces used for logging and creating publishers and subscribers
......
......@@ -65,7 +65,8 @@ FootprintSubscriber::FootprintSubscriber(
bool
FootprintSubscriber::getFootprint(
std::vector<geometry_msgs::msg::Point> & footprint,
rclcpp::Time & stamp)
rclcpp::Time & stamp,
rclcpp::Duration valid_footprint_timeout)
{
if (!footprint_received_) {
return false;
......@@ -75,7 +76,7 @@ FootprintSubscriber::getFootprint(
std::make_shared<geometry_msgs::msg::Polygon>(footprint_->polygon));
auto & footprint_stamp = footprint_->header.stamp;
if (stamp - footprint_stamp > footprint_timeout_) {
if (stamp - footprint_stamp > valid_footprint_timeout) {
return false;
}
......@@ -83,10 +84,19 @@ FootprintSubscriber::getFootprint(
}
bool
FootprintSubscriber::getFootprint(std::vector<geometry_msgs::msg::Point> & footprint)
FootprintSubscriber::getFootprint(
std::vector<geometry_msgs::msg::Point> & footprint,
rclcpp::Duration & valid_footprint_timeout)
{
rclcpp::Time t = node_clock_->get_clock()->now();
return getFootprint(footprint, t);
return getFootprint(footprint, t, valid_footprint_timeout);
}
bool
FootprintSubscriber::getFootprint(
std::vector<geometry_msgs::msg::Point> & footprint)
{
return getFootprint(footprint, footprint_timeout_);
}
void
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment