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.
WMListener.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2022 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
19#include <functional>
20#include <mutex>
21#include <rclcpp/rclcpp.hpp>
23#include <carma_ros2_utils/carma_ros2_utils.hpp>
24#include <autoware_lanelet2_msgs/msg/map_bin.hpp>
25#include <queue>
26#include <carma_perception_msgs/msg/roadway_obstacle_list.hpp>
27#include <carma_planning_msgs/msg/route.hpp>
28#include <carma_v2x_msgs/msg/spat.hpp>
29#include <carma_ros2_utils/carma_lifecycle_node.hpp>
30#include <rosgraph_msgs/msg/clock.hpp>
32
33
34namespace carma_wm
35{
36class WMListenerWorker; // Forward declaration of worker class
37
49{
50public:
60 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
61 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
62 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics,
63 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params_,
64 bool multi_thread = false);
65
69
76
84 void setMapCallback(std::function<void()> callback);
85
93 void setRouteCallback(std::function<void()> callback);
94
105 std::unique_lock<std::mutex> getLock(bool pre_locked = true);
106
114 void setConfigSpeedLimit(double config_lim) const;
115
120 void setWMSpatProcessingState(const
121 carma_wm::SIGNAL_PHASE_PROCESSING& phase_type) const;
122
128
134
142
143
144private:
145 // Callback function that uses lock to edit the map
146 void mapUpdateCallback(autoware_lanelet2_msgs::msg::MapBin::SharedPtr geofence_msg);
147 carma_ros2_utils::SubPtr<carma_perception_msgs::msg::RoadwayObstacleList> roadway_objects_sub_;
148 carma_ros2_utils::SubPtr<autoware_lanelet2_msgs::msg::MapBin> map_update_sub_;
149
150 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
151 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
152 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
153 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params_;
154
155 std::unique_ptr<WMListenerWorker> worker_;
156
157 carma_ros2_utils::SubPtr<autoware_lanelet2_msgs::msg::MapBin> map_sub_;
158 carma_ros2_utils::SubPtr<carma_planning_msgs::msg::Route> route_sub_;
159 carma_ros2_utils::SubPtr<carma_v2x_msgs::msg::SPAT> traffic_spat_sub_;
160 carma_ros2_utils::SubPtr<rosgraph_msgs::msg::Clock> sim_clock_sub_;
161 carma_ros2_utils::SubPtr<rosgraph_msgs::msg::Clock> ros1_clock_sub_;
162 const bool multi_threaded_;
163 std::mutex mw_mutex_;
164
165
166};
167} // namespace carma_wm
Class which provies automated subscription and threading support for the world model.
Definition: WMListener.hpp:49
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_
Definition: WMListener.hpp:151
void mapUpdateCallback(autoware_lanelet2_msgs::msg::MapBin::SharedPtr geofence_msg)
Definition: WMListener.cpp:190
void setConfigSpeedLimit(double config_lim) const
Allows user to set a callback to be triggered when a route update is received NOTE: If operating in m...
Definition: WMListener.cpp:222
carma_ros2_utils::SubPtr< autoware_lanelet2_msgs::msg::MapBin > map_update_sub_
Definition: WMListener.hpp:148
void setMapCallback(std::function< void()> callback)
Allows user to set a callback to be triggered when a map update is received NOTE: If operating in mul...
Definition: WMListener.cpp:199
WorldModelConstPtr getWorldModel()
Returns a pointer to an intialized world model instance.
Definition: WMListener.cpp:184
carma_ros2_utils::SubPtr< rosgraph_msgs::msg::Clock > sim_clock_sub_
Definition: WMListener.hpp:160
carma_ros2_utils::SubPtr< rosgraph_msgs::msg::Clock > ros1_clock_sub_
Definition: WMListener.hpp:161
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_
Definition: WMListener.hpp:152
~WMListener()
Destructor.
Definition: WMListener.cpp:170
carma_ros2_utils::SubPtr< autoware_lanelet2_msgs::msg::MapBin > map_sub_
Definition: WMListener.hpp:157
std::unique_ptr< WMListenerWorker > worker_
Definition: WMListener.hpp:155
void enableUpdatesWithoutRouteWL()
Use to allow updates to occur even if they invalidate the current route. This is only meant to be use...
Definition: WMListener.cpp:172
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params_
Definition: WMListener.hpp:153
carma_ros2_utils::SubPtr< carma_perception_msgs::msg::RoadwayObstacleList > roadway_objects_sub_
Definition: WMListener.hpp:147
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_
Definition: WMListener.hpp:150
void setRouteCallback(std::function< void()> callback)
Allows user to set a callback to be triggered when a route update is received NOTE: If operating in m...
Definition: WMListener.cpp:205
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::Route > route_sub_
Definition: WMListener.hpp:158
void setWMSpatProcessingState(const carma_wm::SIGNAL_PHASE_PROCESSING &phase_type) const
Activate SPAT processor, which is turned off by default, with OFF (0), ON (1)
Definition: WMListener.cpp:227
carma_wm::SIGNAL_PHASE_PROCESSING getWMSpatProcessingState() const
Get World Model SPAT processor state.
Definition: WMListener.cpp:233
WMListener(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics, rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params_, bool multi_thread=false)
Constructor which can be used to specify threading behavior of this class.
Definition: WMListener.cpp:25
const bool multi_threaded_
Definition: WMListener.hpp:162
bool checkIfReRoutingNeededWL()
Returns true if a map update has been processed which requires rerouting. This method is meant to be ...
Definition: WMListener.cpp:178
std::unique_lock< std::mutex > getLock(bool pre_locked=true)
Returns a unique_lock which can be used to lock world model updates until the user finishes a desired...
Definition: WMListener.cpp:211
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::SPAT > traffic_spat_sub_
Definition: WMListener.hpp:159
bool callback(cav_srvs::PlanTrajectory::Request &req, cav_srvs::PlanTrajectory::Response &res)
Definition: helper.cpp:21
std::shared_ptr< const WorldModel > WorldModelConstPtr
Definition: WorldModel.hpp:454