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.
intersection_transit_maneuvering_node.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2023 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>
21#include <carma_planning_msgs/msg/plugin.hpp>
22#include <carma_ros2_utils/carma_lifecycle_node.hpp>
23#include <carma_planning_msgs/srv/plan_trajectory.hpp>
24#include <functional>
27
29{
34{
35 private:
36
37 // Worker object
38
39 std::vector<carma_planning_msgs::msg::Maneuver> converted_maneuvers_;
40 carma_planning_msgs::msg::VehicleState vehicle_state_;
41
42 public:
43 std::shared_ptr<CallInterface> object_;
44 carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory> client_;
48 explicit IntersectionTransitManeuveringNode(const rclcpp::NodeOptions &);
49
57 std::vector<carma_planning_msgs::msg::Maneuver> convert_maneuver_plan(const std::vector<carma_planning_msgs::msg::Maneuver>& maneuvers);
58
60 // Overrides
63 std::shared_ptr<rmw_request_id_t>,
64 carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req,
65 carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp) override;
66
67 bool get_availability() override;
68
69 std::string get_version_id() override;
70
74 carma_ros2_utils::CallbackReturn on_configure_plugin() override;
75
76};
77
78
79} //intersection_transit_maneuvering
TacticalPlugin base class which can be extended by user provided plugins which wish to implement the ...
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > client_
std::vector< carma_planning_msgs::msg::Maneuver > convert_maneuver_plan(const std::vector< carma_planning_msgs::msg::Maneuver > &maneuvers)
Converts a sequence of INTERSECTION_TRANSIT maneuvers to LANE_FOLLOWING maneuvers.
IntersectionTransitManeuveringNode(const rclcpp::NodeOptions &)
IntersectionTransitManeuveringNode constructor.
bool get_availability() override
Get the availability status of this plugin based on the current operating environment....
carma_ros2_utils::CallbackReturn on_configure_plugin() override
This method should be used to load parameters and will be called on the configure state transition.
std::string get_version_id() override
Returns the version id of this plugin.
void plan_trajectory_callback(std::shared_ptr< rmw_request_id_t >, carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req, carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp) override
Extending class provided callback which should return a planned trajectory based on the provided traj...