21using std::placeholders::_1;
24 : timerFactory_(timerFactory)
50 std::lock_guard<std::mutex> guard(
mutex_);
57 if (it->second.second)
72 std::lock_guard<std::mutex> guard(
mutex_);
74 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"carma_wm_ctrl"),
"Attempting to add Geofence with Id: " << gf_ptr->id_);
77 for (
size_t schedule_idx = 0; schedule_idx < gf_ptr->schedules.size(); schedule_idx++)
80 auto interval_info = gf_ptr->schedules[schedule_idx].getNextInterval(
timerFactory_->now());
81 rclcpp::Time startTime = interval_info.second;
83 if (!interval_info.first && startTime == rclcpp::Time(0, 0,
clock_type_))
85 RCLCPP_WARN_STREAM(rclcpp::get_logger(
"carma_wm_ctrl"),
86 "Failed to add geofence as its schedule did not contain an active or upcoming control period. GF Id: "
91 if (interval_info.first)
96 int32_t timer_id =
nextId();
98 rclcpp::Duration control_duration = rclcpp::Duration(std::max((startTime -
timerFactory_->now()).seconds() * 1e9, 0.0));
102 timer_id, control_duration,
105 timers_[timer_id] = std::make_pair(std::move(timer),
false);
112 std::lock_guard<std::mutex> guard(
mutex_);
113 rclcpp::Time endTime =
timerFactory_->now() + gf_ptr->schedules[schedule_id].control_span_;
115 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"carma_wm_ctrl"),
"Activating Geofence with Id: " << gf_ptr->id_ <<
", which will end at:" << endTime.seconds());
120 int32_t ending_timer_id =
nextId();
122 rclcpp::Duration control_duration = rclcpp::Duration(std::max((endTime -
timerFactory_->now()).seconds() * 1e9, 0.0));
125 ending_timer_id, control_duration,
127 timers_[ending_timer_id] = std::make_pair(std::move(timer),
false);
129 timers_[timer_id].second =
true;
134 std::lock_guard<std::mutex> guard(
mutex_);
136 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"carma_wm_ctrl"),
"Deactivating Geofence with Id: " << gf_ptr->id_);
139 timers_[timer_id].second =
true;
142 auto interval_info = gf_ptr->schedules[schedule_id].getNextInterval(
timerFactory_->now());
143 rclcpp::Time startTime = interval_info.second;
146 if (interval_info.first)
151 if (!interval_info.first && startTime == rclcpp::Time(0, 0,
clock_type_))
158 int32_t start_timer_id =
nextId();
160 rclcpp::Duration control_duration = rclcpp::Duration(std::max((startTime -
timerFactory_->now()).seconds() * 1e9, 0.0));
163 start_timer_id, control_duration,
166 timers_[start_timer_id] = std::make_pair(std::move(timer),
false);
171 std::lock_guard<std::mutex> guard(
mutex_);
177 std::lock_guard<std::mutex> guard(
mutex_);
void onGeofenceActive(std::function< void(std::shared_ptr< Geofence >)> active_callback)
Method which allows the user to set a callback which will be triggered when a geofence becomes active...
void endGeofenceCallback(std::shared_ptr< Geofence > gf_ptr, const unsigned int schedule_id, const int32_t timer_id)
The callback which is triggered when a geofence becomes in-active This will call the user set inactiv...
std::unique_ptr< Timer > TimerPtr
rcl_clock_type_t clock_type_
rcl_clock_type_t getClockType()
Get the clock type of the clock being created by the timer factory.
GeofenceScheduler(std::shared_ptr< TimerFactory > timerFactory)
Constructor which takes in a TimerFactory. Timers from this factory will be used to generate the trig...
std::function< void(std::shared_ptr< Geofence >)> active_callback_
rclcpp::Time now()
Get current time used by scheduler.
void startGeofenceCallback(std::shared_ptr< Geofence > gf_ptr, const unsigned int schedule_id, const int32_t timer_id)
The callback which is triggered when a geofence becomes active This will call the user set active_cal...
uint32_t nextId()
Generates the next id to be used for a timer.
std::unique_ptr< Timer > deletion_timer_
std::function< void(std::shared_ptr< Geofence >)> inactive_callback_
void addGeofence(std::shared_ptr< Geofence > gf_ptr)
Add a geofence to the scheduler. This will cause it to trigger an event when it becomes active or goe...
void onGeofenceInactive(std::function< void(std::shared_ptr< Geofence >)> inactive_callback)
Method which allows the user to set a callback which will be triggered when a geofence becomes in-act...
std::unordered_map< uint32_t, std::pair< TimerPtr, bool > > timers_
std::shared_ptr< TimerFactory > timerFactory_
void clearTimers()
Clears the expired timers from the memory of this scheduler.