19#include <rclcpp/rclcpp.hpp>
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>
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>
43#include <wgs84_utils/wgs84_utils.h>
44#include <boost/filesystem.hpp>
45#include <boost/optional.hpp>
47#include <unordered_set>
49#include <tf2_ros/transform_listener.h>
50#include <tf2/LinearMath/Transform.h>
51#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
86 void setLoggerInterface(rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger);
92 void setClock(rclcpp::Clock::SharedPtr clock);
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,
114 const std::shared_ptr<carma_planning_msgs::srv::GetAvailableRoutes::Request>,
115 std::shared_ptr<carma_planning_msgs::srv::GetAvailableRoutes::Response> resp);
124 const std::shared_ptr<carma_planning_msgs::srv::SetActiveRoute::Request> req,
125 std::shared_ptr<carma_planning_msgs::srv::SetActiveRoute::Response> resp);
133 const std::shared_ptr<carma_planning_msgs::srv::AbortActiveRoute::Request>,
134 std::shared_ptr<carma_planning_msgs::srv::AbortActiveRoute::Response> resp);
145 void twistCb(geometry_msgs::msg::TwistStamped::UniquePtr msg);
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);
200 carma_planning_msgs::msg::Route
composeRouteMsg(
const lanelet::Optional<lanelet::routing::Route>&
route)
const;
220 bool crosstrackErrorCheck(
const std::shared_ptr<geometry_msgs::msg::PoseStamped>& msg, lanelet::ConstLanelet current_llt);
252 lanelet::Optional<lanelet::routing::Route>
rerouteAfterRouteInvalidation(
const std::vector<lanelet::BasicPoint2d>& destination_points_in_map);
316 carma_ros2_utils::PubPtr<carma_planning_msgs::msg::Route>
route_pub_;
343 geometry_msgs::msg::TransformStamped
tf_;
351 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
logger_;
tf2::Stamped< tf2::Transform > frontbumper_transform_
static constexpr double epsilon_
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...
bool new_route_msg_generated_
void addLanelet(lanelet::ConstLanelet llt)
double current_downtrack_distance_
RouteStateWorker rs_worker_
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.
double ll_crosstrack_distance_
bool new_route_marker_generated_
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.
tf2_ros::Buffer & tf2_buffer_
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_
lanelet::BasicPoint2d current_loc_
std::string route_file_path_
double down_track_target_range_
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.
rclcpp::Clock::SharedPtr clock_
lanelet::ConstLanelets route_llts
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)
double ll_downtrack_distance_
double current_crosstrack_distance_
std::shared_ptr< const WorldModel > WorldModelConstPtr
std::shared_ptr< const lanelet::routing::RoutingGraph > LaneletRoutingGraphConstPtr