17#include <unordered_set>
18#include <boost/date_time/gregorian/greg_weekday.hpp>
19#include <boost/date_time/gregorian/greg_date.hpp>
20#include <rclcpp/rclcpp.hpp>
21#include <rclcpp/duration.hpp>
22#include <lanelet2_extension/time/TimeConversion.h>
39 std::unordered_set<boost::gregorian::greg_weekday, std::hash<int>>;
60 GeofenceSchedule(rclcpp::Time schedule_start, rclcpp::Time schedule_end, rclcpp::Duration control_start,
61 rclcpp::Duration control_duration, rclcpp::Duration control_offset, rclcpp::Duration control_span, rclcpp::Duration control_period,
96 std::pair<bool, rclcpp::Time>
getNextInterval(
const rclcpp::Time& time)
const;
bool scheduleStarted(const rclcpp::Time &time) const
Returns true if the schedule has started by the provided time.
rclcpp::Duration control_span_
rclcpp::Time schedule_start_
rclcpp::Duration control_start_
std::pair< bool, rclcpp::Time > getNextInterval(const rclcpp::Time &time) const
Returns the start time of the next active interval defined by this schedule.
rclcpp::Duration control_period_
rclcpp::Time schedule_end_
GeofenceSchedule()
Default Constructor does not initialize any members.
std::unordered_set< boost::gregorian::greg_weekday, std::hash< int > > DayOfTheWeekSet
DayOfTheWeekSet week_day_set_
rclcpp::Duration control_offset_
bool scheduleExpired(const rclcpp::Time &time) const
Returns true if the schedule has expired by the provided time.
rclcpp::Duration control_duration_