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.
port_drayage_plugin.hpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2020-2022 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
16
17#pragma once
18
19#include <rclcpp/rclcpp.hpp>
20#include <functional>
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>
29
30#include <carma_ros2_utils/carma_lifecycle_node.hpp>
33
35{
36
43 class PortDrayagePlugin : public carma_ros2_utils::CarmaLifecycleNode
44 {
45
46 private:
47 // Subscribers
48 carma_ros2_utils::SubPtr<geometry_msgs::msg::PoseStamped> pose_subscriber_;
49 carma_ros2_utils::SubPtr<carma_v2x_msgs::msg::MobilityOperation> inbound_mobility_operation_subscriber_;
50 carma_ros2_utils::SubPtr<carma_planning_msgs::msg::GuidanceState> guidance_state_subscriber_;
51 carma_ros2_utils::SubPtr<carma_planning_msgs::msg::RouteEvent> route_event_subscriber_;
52 carma_ros2_utils::SubPtr<std_msgs::msg::String> georeference_subscriber_;
53
54 // Publishers
55 carma_ros2_utils::PubPtr<carma_v2x_msgs::msg::MobilityOperation> outbound_mobility_operations_publisher_;
56 carma_ros2_utils::PubPtr<carma_msgs::msg::UIInstructions> ui_instructions_publisher_;
57
58 // Service Clients
59 carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::SetActiveRoute> set_active_route_client_;
60
61 // Node configuration
63
64 // PortDrayageWorker object
66
67 public:
71 explicit PortDrayagePlugin(const rclcpp::NodeOptions &);
72
78 bool callSetActiveRouteClient(std::shared_ptr<carma_planning_msgs::srv::SetActiveRoute::Request> req);
79
84 void publishMobilityOperation(const carma_v2x_msgs::msg::MobilityOperation& msg);
85
90 void publishUIInstructions(const carma_msgs::msg::UIInstructions& msg);
91
95 rcl_interfaces::msg::SetParametersResult
96 parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters);
97
99 // Overrides
101 carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &prev_state);
102 };
103
104} // port_drayage_plugin
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 > &parameters)
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.