Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
GeofenceSchedule.hpp
Go to the documentation of this file.
1#pragma once
2/*
3 * Copyright (C) 2022 LEIDOS.
4 *
5 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
6 * use this file except in compliance with the License. You may obtain a copy of
7 * the License at
8 *
9 * http://www.apache.org/licenses/LICENSE-2.0
10 *
11 * Unless required by applicable law or agreed to in writing, software
12 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
13 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
14 * License for the specific language governing permissions and limitations under
15 * the License.
16 */
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>
23
24namespace carma_wm_ctrl
25{
27{
28public:
29 rclcpp::Time schedule_start_; // Overall schedule start
30 rclcpp::Time schedule_end_; // Overall schedule end
31
32 rclcpp::Duration control_start_{0, 0}; // Duration from start of day
33 rclcpp::Duration control_duration_{0, 0}; // Duration from start of control_start
34 rclcpp::Duration control_offset_{0, 0}; // Duration from start of day (specifies start time for repeat parameters - span period)
35 rclcpp::Duration control_span_{0, 0}; // Duration of active status. Starts from offset
36 rclcpp::Duration control_period_{0, 0}; // Interval between active status within control_duration since control_start
37
39 std::unordered_set<boost::gregorian::greg_weekday, std::hash<int>>; // Set of week days where geofence is active.
40 // Uses int hashing function
41 DayOfTheWeekSet week_day_set_; // NOTE: If no day of the week is included then all should be
42
47
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,
62 DayOfTheWeekSet week_day_set = { 0, 1, 2, 3, 4, 5, 6 }); // Include all weekdays as default (0-6) ->
63 // (Sun-Sat)
64
72 bool scheduleExpired(const rclcpp::Time& time) const;
73
81 bool scheduleStarted(const rclcpp::Time& time) const;
82
96 std::pair<bool, rclcpp::Time> getNextInterval(const rclcpp::Time& time) const;
97};
98} // namespace carma_wm_ctrl
bool scheduleStarted(const rclcpp::Time &time) const
Returns true if the schedule has started by the provided time.
std::pair< bool, rclcpp::Time > getNextInterval(const rclcpp::Time &time) const
Returns the start time of the next active interval defined by this schedule.
GeofenceSchedule()
Default Constructor does not initialize any members.
std::unordered_set< boost::gregorian::greg_weekday, std::hash< int > > DayOfTheWeekSet
bool scheduleExpired(const rclcpp::Time &time) const
Returns true if the schedule has expired by the provided time.