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.
route_generator_worker.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2020-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 <rclcpp/rclcpp.hpp>
20
21#include <carma_planning_msgs/msg/route.hpp>
22#include <carma_planning_msgs/msg/route_state.hpp>
23#include <carma_planning_msgs/msg/route_event.hpp>
24#include <geometry_msgs/msg/pose_stamped.hpp>
25#include <geometry_msgs/msg/twist_stamped.hpp>
26#include <visualization_msgs/msg/marker.hpp>
27#include <visualization_msgs/msg/marker_array.hpp>
28#include <std_msgs/msg/string.hpp>
29#include <carma_planning_msgs/srv/get_available_routes.hpp>
30#include <carma_planning_msgs/srv/set_active_route.hpp>
31#include <carma_planning_msgs/srv/abort_active_route.hpp>
32
35#include <carma_wm/Geometry.hpp>
36
37#include <lanelet2_core/geometry/Lanelet.h>
38#include <lanelet2_core/primitives/Lanelet.h>
39#include <lanelet2_extension/projection/local_frame_projector.h>
40#include <lanelet2_extension/io/autoware_osm_parser.h>
41#include <lanelet2_core/utility/Utilities.h>
42
43#include <wgs84_utils/wgs84_utils.h>
44#include <boost/filesystem.hpp>
45#include <boost/optional.hpp>
46#include <math.h>
47#include <unordered_set>
48#include <functional>
49#include <tf2_ros/transform_listener.h>
50#include <tf2/LinearMath/Transform.h>
51#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
52
54
55namespace route {
56
58 {
59
60 public:
64 RouteGeneratorWorker(tf2_ros::Buffer& tf2_buffer);
65
69 std::function<bool()> reroutingChecker;
70
74 void setReroutingChecker(const std::function<bool()> inputFunction);
75
81
86 void setLoggerInterface(rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger);
87
92 void setClock(rclcpp::Clock::SharedPtr clock);
93
102 lanelet::Optional<lanelet::routing::Route> routing(const lanelet::BasicPoint2d start,
103 const std::vector<lanelet::BasicPoint2d>& via,
104 const lanelet::BasicPoint2d end,
105 const lanelet::LaneletMapConstPtr map_pointer,
106 const carma_wm::LaneletRoutingGraphConstPtr graph_pointer) const;
107
113 bool getAvailableRouteCb(const std::shared_ptr<rmw_request_id_t>,
114 const std::shared_ptr<carma_planning_msgs::srv::GetAvailableRoutes::Request>,
115 std::shared_ptr<carma_planning_msgs::srv::GetAvailableRoutes::Response> resp);
116
123 bool setActiveRouteCb(const std::shared_ptr<rmw_request_id_t>,
124 const std::shared_ptr<carma_planning_msgs::srv::SetActiveRoute::Request> req,
125 std::shared_ptr<carma_planning_msgs::srv::SetActiveRoute::Response> resp);
126
132 bool abortActiveRouteCb(const std::shared_ptr<rmw_request_id_t>,
133 const std::shared_ptr<carma_planning_msgs::srv::AbortActiveRoute::Request>,
134 std::shared_ptr<carma_planning_msgs::srv::AbortActiveRoute::Response> resp);
135
139 void bumperPoseCb();
140
145 void twistCb(geometry_msgs::msg::TwistStamped::UniquePtr msg);
146
151 void georeferenceCb(std_msgs::msg::String::UniquePtr msg);
152
157 void setRouteFilePath(const std::string& path);
158
163 void setDowntrackDestinationRange(double dt_dest_range);
164
172 void setPublishers(const carma_ros2_utils::PubPtr<carma_planning_msgs::msg::RouteEvent>& route_event_pub,
173 const carma_ros2_utils::PubPtr<carma_planning_msgs::msg::RouteState>& route_state_pub,
174 const carma_ros2_utils::PubPtr<carma_planning_msgs::msg::Route>& route_pub,
175 const carma_ros2_utils::PubPtr<visualization_msgs::msg::Marker>& route_marker_pub);
176
182 bool checkForDuplicateLaneletsInShortestPath(const lanelet::routing::Route& route) const;
183
188 std::vector<lanelet::BasicPoint3d> loadRouteDestinationsInMapFrame(const std::vector<carma_v2x_msgs::msg::Position3D>& destinations) const;
189
194 std::vector<carma_v2x_msgs::msg::Position3D> loadRouteDestinationGpsPointsFromRouteId(const std::string& route_id) const;
195
200 carma_planning_msgs::msg::Route composeRouteMsg(const lanelet::Optional<lanelet::routing::Route>& route) const;
201
205 bool spinCallback();
206
211 visualization_msgs::msg::Marker composeRouteMarkerMsg(const lanelet::Optional<lanelet::routing::Route>& route);
212
220 bool crosstrackErrorCheck(const std::shared_ptr<geometry_msgs::msg::PoseStamped>& msg, lanelet::ConstLanelet current_llt);
221
227 void setCrosstrackErrorCountMax(int cte_max);
228
234 void setCrosstrackErrorDistance(double cte_dist);
235
242 lanelet::ConstLanelet getClosestLaneletFromRouteLanelets(lanelet::BasicPoint2d position) const;
243
244 // Added for Unit Testing
245 void addLanelet(lanelet::ConstLanelet llt);
246
252 lanelet::Optional<lanelet::routing::Route> rerouteAfterRouteInvalidation(const std::vector<lanelet::BasicPoint2d>& destination_points_in_map);
253
258
259 // Current vehicle pose if it has been recieved
260 boost::optional<geometry_msgs::msg::PoseStamped> vehicle_pose_;
261
262 private:
263
264 const double DEG_TO_RAD = 0.0174533;
265
266 // route state worker
268
269 // directory of route files
270 std::string route_file_path_;
271
272 // const pointer to world model object
274
275 // route messages waiting to be updated and published
276 carma_planning_msgs::msg::Route route_msg_;
277 carma_planning_msgs::msg::RouteEvent route_event_msg_;
278 carma_planning_msgs::msg::RouteState route_state_msg_;
279 visualization_msgs::msg::Marker route_marker_msg_;
280
281 std::vector<lanelet::ConstPoint3d> points_;
282
283 //List of lanelets in the route
284 lanelet::ConstLanelets route_llts;
285
286 // minimum down track error which can trigger route complete event
288
289 // current cross track distance
291
292 // current down track distance relevant to the route
294
295 // current pose
296 lanelet::BasicPoint2d current_loc_;
297
298 // current lanelet cross track distance
300
301 // current lanelet down track
303
304 lanelet::Id ll_id_;
305
306 // current speed limit on current lanelet
307 double speed_limit_ = 0;
308 // Current vehicle forward speed
309 double current_speed_ = 0;
310 //A small static value for comparing doubles
311 static constexpr double epsilon_ = 0.001;
312
313 // local copy of Route publihsers
314 carma_ros2_utils::PubPtr<carma_planning_msgs::msg::RouteEvent> route_event_pub_;
315 carma_ros2_utils::PubPtr<carma_planning_msgs::msg::RouteState> route_state_pub_;
316 carma_ros2_utils::PubPtr<carma_planning_msgs::msg::Route> route_pub_;
317 carma_ros2_utils::PubPtr<visualization_msgs::msg::Marker> route_marker_pub_;
318
319 // a bool flag indicates a new route has been generated such that a local copy of Route message should be published again
322
323 // a queue of route event. All events in the queue will be published in order on each spin.
324 std::queue<uint8_t> route_event_queue;
325
326 // private helper function to add a new route event into event queue
327 void publishRouteEvent(uint8_t event_type);
328
329 // maximum cross track error which can trigger left route event
331
332 // counter to record how many times vehicle's position exceeds crosstrack distance
333 int cte_count_ = 0;
334
336
337 // destination points in map
338 std::vector<lanelet::BasicPoint2d> destination_points_in_map_;
339
340 // The current map projection for lat/lon to map frame conversion
341 boost::optional<std::string> map_proj_;
342
343 geometry_msgs::msg::TransformStamped tf_;
344 tf2::Stamped<tf2::Transform> frontbumper_transform_;
345
346 // TF listenser
347 tf2_ros::Buffer& tf2_buffer_;
348 std::unique_ptr<tf2_ros::TransformListener> tf2_listener_;
349
350 // Logger interface
351 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_;
352
353 rclcpp::Clock::SharedPtr clock_;
354 };
355
356} // namespace route
tf2::Stamped< tf2::Transform > frontbumper_transform_
bool setActiveRouteCb(const std::shared_ptr< rmw_request_id_t >, const std::shared_ptr< carma_planning_msgs::srv::SetActiveRoute::Request > req, std::shared_ptr< carma_planning_msgs::srv::SetActiveRoute::Response > resp)
Set_active_route service callback. User can select a route to start following by calling this service...
void setCrosstrackErrorDistance(double cte_dist)
set the maximum crosstrack error distance
bool getAvailableRouteCb(const std::shared_ptr< rmw_request_id_t >, const std::shared_ptr< carma_planning_msgs::srv::GetAvailableRoutes::Request >, std::shared_ptr< carma_planning_msgs::srv::GetAvailableRoutes::Response > resp)
Get_available_route service callback. Calls to this service will respond with a list of route names f...
void addLanelet(lanelet::ConstLanelet llt)
void setLoggerInterface(rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger)
Dependency injection for logger interface.
void setWorldModelPtr(carma_wm::WorldModelConstPtr wm)
Dependency injection for world model pointer.
std::vector< lanelet::BasicPoint2d > destination_points_in_map_
void setRouteFilePath(const std::string &path)
Set method for configurable parameter.
void initializeBumperTransformLookup()
Initialize transform lookup from front bumper to map.
void setClock(rclcpp::Clock::SharedPtr clock)
Dependency injection for clock object.
void bumperPoseCb()
Callback for the front bumper pose transform.
void setReroutingChecker(const std::function< bool()> inputFunction)
setReroutingChecker function to set the rerouting flag
lanelet::Optional< lanelet::routing::Route > rerouteAfterRouteInvalidation(const std::vector< lanelet::BasicPoint2d > &destination_points_in_map)
After route is invalidated, this function returns a new route based on the destinations points.
void setCrosstrackErrorCountMax(int cte_max)
set the crosstrack error counter maximum limit
void setDowntrackDestinationRange(double dt_dest_range)
Set method for configurable parameter.
lanelet::ConstLanelet getClosestLaneletFromRouteLanelets(lanelet::BasicPoint2d position) const
"Get the closest lanelet on the route relative to the vehicle's current position. If the input list d...
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_
boost::optional< std::string > map_proj_
visualization_msgs::msg::Marker composeRouteMarkerMsg(const lanelet::Optional< lanelet::routing::Route > &route)
composeRouteMarkerMsg is a function to generate route rviz markers
carma_ros2_utils::PubPtr< carma_planning_msgs::msg::Route > route_pub_
visualization_msgs::msg::Marker route_marker_msg_
bool spinCallback()
Spin callback which will be called frequently based on spin rate.
std::vector< lanelet::ConstPoint3d > points_
geometry_msgs::msg::TransformStamped tf_
void twistCb(geometry_msgs::msg::TwistStamped::UniquePtr msg)
Callback for the twist subscriber, which will store latest twist locally.
RouteGeneratorWorker(tf2_ros::Buffer &tf2_buffer)
Constructor for RouteGeneratorWorker class taking in dependencies via dependency injection.
carma_ros2_utils::PubPtr< carma_planning_msgs::msg::RouteEvent > route_event_pub_
std::vector< lanelet::BasicPoint3d > loadRouteDestinationsInMapFrame(const std::vector< carma_v2x_msgs::msg::Position3D > &destinations) const
Function to take route destination points from a vector of 3D points and convert them from lat/lon va...
carma_ros2_utils::PubPtr< carma_planning_msgs::msg::RouteState > route_state_pub_
std::function< bool()> reroutingChecker
reroutingChecker function to set the rerouting flag locally
carma_wm::WorldModelConstPtr world_model_
carma_planning_msgs::msg::RouteEvent route_event_msg_
lanelet::Optional< lanelet::routing::Route > routing(const lanelet::BasicPoint2d start, const std::vector< lanelet::BasicPoint2d > &via, const lanelet::BasicPoint2d end, const lanelet::LaneletMapConstPtr map_pointer, const carma_wm::LaneletRoutingGraphConstPtr graph_pointer) const
Generate Lanelet2 route based on input destinations.
carma_planning_msgs::msg::Route route_msg_
std::vector< carma_v2x_msgs::msg::Position3D > loadRouteDestinationGpsPointsFromRouteId(const std::string &route_id) const
Function to load route destination points from a route file and store them in a vector of 3D points.
carma_planning_msgs::msg::Route composeRouteMsg(const lanelet::Optional< lanelet::routing::Route > &route) const
Helper function to generate a CARMA route message based on planned lanelet route.
void setPublishers(const carma_ros2_utils::PubPtr< carma_planning_msgs::msg::RouteEvent > &route_event_pub, const carma_ros2_utils::PubPtr< carma_planning_msgs::msg::RouteState > &route_state_pub, const carma_ros2_utils::PubPtr< carma_planning_msgs::msg::Route > &route_pub, const carma_ros2_utils::PubPtr< visualization_msgs::msg::Marker > &route_marker_pub)
Method to pass publishers into worker class.
carma_planning_msgs::msg::RouteState route_state_msg_
std::unique_ptr< tf2_ros::TransformListener > tf2_listener_
bool crosstrackErrorCheck(const std::shared_ptr< geometry_msgs::msg::PoseStamped > &msg, lanelet::ConstLanelet current_llt)
crosstrackErrorCheck is a function that determines when the vehicle has left the route and reports wh...
void georeferenceCb(std_msgs::msg::String::UniquePtr msg)
Callback for the georeference subscriber used to set the map projection.
carma_ros2_utils::PubPtr< visualization_msgs::msg::Marker > route_marker_pub_
bool abortActiveRouteCb(const std::shared_ptr< rmw_request_id_t >, const std::shared_ptr< carma_planning_msgs::srv::AbortActiveRoute::Request >, std::shared_ptr< carma_planning_msgs::srv::AbortActiveRoute::Response > resp)
Abort_active_route service callback. User can call this service to abort a current following route an...
bool checkForDuplicateLaneletsInShortestPath(const lanelet::routing::Route &route) const
Helper function to check whether a route's shortest path contains any duplicate Lanelet IDs....
boost::optional< geometry_msgs::msg::PoseStamped > vehicle_pose_
std::queue< uint8_t > route_event_queue
void publishRouteEvent(uint8_t event_type)
std::shared_ptr< const WorldModel > WorldModelConstPtr
Definition: WorldModel.hpp:452
std::shared_ptr< const lanelet::routing::RoutingGraph > LaneletRoutingGraphConstPtr
Definition: WorldModel.hpp:51