19#include <rclcpp/rclcpp.hpp>
21#include <std_msgs/msg/string.hpp>
22#include <carma_v2x_msgs/msg/mobility_operation.hpp>
23#include <carma_planning_msgs/msg/guidance_state.hpp>
24#include <carma_planning_msgs/msg/route_event.hpp>
25#include <carma_planning_msgs/srv/set_active_route.hpp>
26#include <carma_msgs/msg/ui_instructions.hpp>
27#include <geometry_msgs/msg/pose_stamped.hpp>
28#include <lanelet2_extension/projection/local_frame_projector.h>
30#include <carma_ros2_utils/carma_lifecycle_node.hpp>
95 rcl_interfaces::msg::SetParametersResult
101 carma_ros2_utils::CallbackReturn
handle_on_configure(
const rclcpp_lifecycle::State &prev_state);
bool callSetActiveRouteClient(std::shared_ptr< carma_planning_msgs::srv::SetActiveRoute::Request > req)
Calls the /guidance/set_active_route service client to set an active route.
carma_ros2_utils::PubPtr< carma_v2x_msgs::msg::MobilityOperation > outbound_mobility_operations_publisher_
carma_ros2_utils::SubPtr< std_msgs::msg::String > georeference_subscriber_
carma_ros2_utils::PubPtr< carma_msgs::msg::UIInstructions > ui_instructions_publisher_
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseStamped > pose_subscriber_
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &prev_state)
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::GuidanceState > guidance_state_subscriber_
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::MobilityOperation > inbound_mobility_operation_subscriber_
void publishMobilityOperation(const carma_v2x_msgs::msg::MobilityOperation &msg)
Publishes a Mobility Operation message to the outgoing mobility operation topic.
PortDrayagePlugin(const rclcpp::NodeOptions &)
PortDrayagePlugin constructor.
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::RouteEvent > route_event_subscriber_
void publishUIInstructions(const carma_msgs::msg::UIInstructions &msg)
Publishes a UI Instructions message to the outgoing UI Instructions topic.
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > ¶meters)
Callback for dynamic parameter updates.
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::SetActiveRoute > set_active_route_client_
Struct containing the algorithm configuration values for port_drayage_plugin.