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.
call_interface.hpp
Go to the documentation of this file.
1#pragma once
2/*
3 * Copyright (C) 2023 LEIDOS.
4 *
5 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
6 * use this file except in compliance with the License. You may obtain a copy of
7 * the License at
8 *
9 * http://www.apache.org/licenses/LICENSE-2.0
10 *
11 * Unless required by applicable law or agreed to in writing, software
12 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
13 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
14 * License for the specific language governing permissions and limitations under
15 * the License.
16 */
17
18#include <rclcpp/rclcpp.hpp>
19#include <string>
20#include <carma_ros2_utils/carma_lifecycle_node.hpp>
21
22
24{
25 public:
26 virtual void call(carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req, carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr& resp) = 0;
27 virtual ~CallInterface() {};
28
34 virtual void set_client(carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory> srv_client) = 0;
35};
virtual void set_client(carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > srv_client)=0
set the trajectory service client
virtual void call(carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req, carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr &resp)=0
virtual ~CallInterface()