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>
26#include <rosgraph_msgs/msg/clock.hpp>
52 void mapCallback(
const autoware_lanelet2_msgs::msg::MapBin::SharedPtr map_msg);
59 void mapUpdateCallback(autoware_lanelet2_msgs::msg::MapBin::SharedPtr geofence_msg);
64 void routeCallback(
const carma_planning_msgs::msg::Route::SharedPtr route_msg);
165 void newRegemUpdateHelper(lanelet::Lanelet parent_llt, lanelet::RegulatoryElement* regem)
const;
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.
double config_speed_limit_
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)
size_t current_map_version_
void isUsingSimTime(bool use_sim_time)
set true if simulation_mode is on
std::string getVehicleParticipationType() const
Returns the Vehicle Participation Type value.
bool recompute_route_flag_
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_
WMListenerWorker()
Constructor.
long most_recent_update_msg_seq_
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)
std::shared_ptr< lanelet::routing::RoutingGraph > LaneletRoutingGraphPtr
std::shared_ptr< const WorldModel > WorldModelConstPtr