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.
WMListenerWorker.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2019-2021 LEIDOS.
5 *
6 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
7 * use this file except in compliance with the License. You may obtain a copy of
8 * the License at
9 *
10 * http://www.apache.org/licenses/LICENSE-2.0
11 *
12 * Unless required by applicable law or agreed to in writing, software
13 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15 * License for the specific language governing permissions and limitations under
16 * the License.
17 */
18#include <autoware_lanelet2_msgs/msg/map_bin.hpp>
19#include <carma_planning_msgs/msg/route.hpp>
20#include <carma_v2x_msgs/msg/spat.hpp>
23#include <queue>
25#include <utility>
26#include <rosgraph_msgs/msg/clock.hpp>
27
28namespace carma_wm
29{
35{
36public:
41
46
52 void mapCallback(const autoware_lanelet2_msgs::msg::MapBin::SharedPtr map_msg);
53
59 void mapUpdateCallback(autoware_lanelet2_msgs::msg::MapBin::SharedPtr geofence_msg);
60
64 void routeCallback(const carma_planning_msgs::msg::Route::SharedPtr route_msg);
65
69 void ros1ClockCallback(const rosgraph_msgs::msg::Clock::SharedPtr clock_msg);
70
74 void simClockCallback(const rosgraph_msgs::msg::Clock::SharedPtr clock_msg);
75
79 void roadwayObjectListCallback(const carma_perception_msgs::msg::RoadwayObstacleList::SharedPtr msg);
80
86 void setMapCallback(std::function<void()> callback);
87
93 void setRouteCallback(std::function<void()> callback);
94
100 void setConfigSpeedLimit(double config_lim);
101
106 double getConfigSpeedLimit() const;
107
108
114 void setVehicleParticipationType(std::string participant);
115
120 std::string getVehicleParticipationType() const;
121
122
127 bool checkIfReRoutingNeeded() const;
133
142 LaneletRoutingGraphPtr routingGraphFromMsg(const autoware_lanelet2_msgs::msg::RoutingGraph& msg, lanelet::LaneletMapPtr map) const;
143
147 void incomingSpatCallback(const carma_v2x_msgs::msg::SPAT::SharedPtr spat_msg);
148
152 void isUsingSimTime(bool use_sim_time);
153
157 void isSpatWallTime(bool is_spat_wall_time);
158
159private:
160 std::shared_ptr<CARMAWorldModel> world_model_;
163 std::function<void()> map_callback_;
164 std::function<void()> route_callback_;
165 void newRegemUpdateHelper(lanelet::Lanelet parent_llt, lanelet::RegulatoryElement* regem) const;
167
168 size_t current_map_version_ = 0; // Current map version based on recived map messages
169 std::queue<autoware_lanelet2_msgs::msg::MapBin::SharedPtr> map_update_queue_; // Update queue used to cache map updates when they cannot be immeadiatly applied due to waiting for rerouting
170 boost::optional<carma_planning_msgs::msg::Route> delayed_route_msg_;
171
172 bool recompute_route_flag_=false; // indicates whether if this node should recompute its route based on invalidated msg
173 bool rerouting_flag_=false; //indicates whether if route node is in middle of rerouting
174 bool route_node_flag_=false; //indicates whether if this node is route node
175 long most_recent_update_msg_seq_ = -1; // Tracks the current sequence number for map update messages. Dropping even a single message would invalidate the map
176
177};
178} // namespace carma_wm
Backend logic class for WMListener.
boost::optional< carma_planning_msgs::msg::Route > delayed_route_msg_
void setConfigSpeedLimit(double config_lim)
Allows user to set a callback to be triggered when a map update is received.
std::function< void()> map_callback_
void isSpatWallTime(bool is_spat_wall_time)
set true if incoming spat is based on wall clock
void mapUpdateCallback(autoware_lanelet2_msgs::msg::MapBin::SharedPtr geofence_msg)
Callback for new map update messages (geofence). Updates the underlying map.
double getConfigSpeedLimit() const
Returns the current configured speed limit value.
void enableUpdatesWithoutRoute()
Enable updates without route and set route_node_flag_ as true.
std::shared_ptr< CARMAWorldModel > world_model_
void setRouteCallback(std::function< void()> callback)
Allows user to set a callback to be triggered when a route update is received.
void newRegemUpdateHelper(lanelet::Lanelet parent_llt, lanelet::RegulatoryElement *regem) const
This is a helper function updates the parent_llt with specified regem. This function is needed as we ...
LaneletRoutingGraphPtr routingGraphFromMsg(const autoware_lanelet2_msgs::msg::RoutingGraph &msg, lanelet::LaneletMapPtr map) const
Helper function to convert a routing graph message into a actual RoutingGraph object.
void routeCallback(const carma_planning_msgs::msg::Route::SharedPtr route_msg)
Callback for route message.
void setMapCallback(std::function< void()> callback)
Allows user to set a callback to be triggered when a map update is received.
bool checkIfReRoutingNeeded() const
Check if re-routing is needed and returns re-routing flag.
void incomingSpatCallback(const carma_v2x_msgs::msg::SPAT::SharedPtr spat_msg)
incoming spat message
void roadwayObjectListCallback(const carma_perception_msgs::msg::RoadwayObstacleList::SharedPtr msg)
Callback for roadway objects msg.
std::function< void()> route_callback_
void mapCallback(const autoware_lanelet2_msgs::msg::MapBin::SharedPtr map_msg)
Callback for new map messages. Updates the underlying map.
void simClockCallback(const rosgraph_msgs::msg::Clock::SharedPtr clock_msg)
Callback for Simulation clock message (used in Simulation runs)
void isUsingSimTime(bool use_sim_time)
set true if simulation_mode is on
std::string getVehicleParticipationType() const
Returns the Vehicle Participation Type value.
WorldModelConstPtr getWorldModel() const
Constructor.
void ros1ClockCallback(const rosgraph_msgs::msg::Clock::SharedPtr clock_msg)
Callback for ROS1 clock message (used in Simulation runs)
std::queue< autoware_lanelet2_msgs::msg::MapBin::SharedPtr > map_update_queue_
void setVehicleParticipationType(std::string participant)
Allows user to set a callback to be triggered when a map update is received.
bool callback(cav_srvs::PlanTrajectory::Request &req, cav_srvs::PlanTrajectory::Response &res)
Definition: helper.cpp:21
std::shared_ptr< lanelet::routing::RoutingGraph > LaneletRoutingGraphPtr
Definition: WorldModel.hpp:50
std::shared_ptr< const WorldModel > WorldModelConstPtr
Definition: WorldModel.hpp:452