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::Servicer Class Reference

#include <itm_service.hpp>

Inheritance diagram for intersection_transit_maneuvering::Servicer:
Inheritance graph
Collaboration diagram for intersection_transit_maneuvering::Servicer:
Collaboration graph

Public Member Functions

 Servicer ()
 Construct a new Servicer object. More...
 
void call (carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req, carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr &resp)
 Method that uses the ros::Service::call() definition as specified in the ROS API. More...
 
void set_client (carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > srv_client)
 set the trajectory service client More...
 
- Public Member Functions inherited from CallInterface
virtual void call (carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req, carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr &resp)=0
 
virtual ~CallInterface ()
 
virtual void set_client (carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > srv_client)=0
 set the trajectory service client More...
 

Private Attributes

carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > client
 

Detailed Description

Definition at line 32 of file itm_service.hpp.

Constructor & Destructor Documentation

◆ Servicer()

intersection_transit_maneuvering::Servicer::Servicer ( )

Construct a new Servicer object.

Definition at line 33 of file itm_service.cpp.

33{};

Member Function Documentation

◆ call()

void intersection_transit_maneuvering::Servicer::call ( carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr  req,
carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr &  resp 
)
virtual

Method that uses the ros::Service::call() definition as specified in the ROS API.

Parameters
reqIncoming PlanTrajectory service request
respIncoming PlanTrajectory service response
Returns
true if successful, otherwise false

Implements CallInterface.

Definition at line 35 of file itm_service.cpp.

36 {
37 std::shared_future<carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr> resp_future = client->async_send_request(req);
38
39 auto future_status = resp_future.wait_for(std::chrono::milliseconds(500));
40
41 if (future_status == std::future_status::ready) {
42 resp = resp_future.get();
43
44 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("intersection_transit_maneuvering"), "Responsible tactical plugin was called and got trajectory size: " << resp->trajectory_plan.trajectory_points.size());
45 }
46 else
47 {
48 RCLCPP_DEBUG(rclcpp::get_logger("intersection_transit_maneuvering"), "Failed to call the responsible tactical plugin from intersection_transit_maneuvering");
49 }
50 return;
51
52 }
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > client
Definition: itm_service.hpp:58

References client.

◆ set_client()

void intersection_transit_maneuvering::Servicer::set_client ( carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory >  srv_client)
virtual

set the trajectory service client

Parameters
clientinput trajectory service client

Implements CallInterface.

Definition at line 55 of file itm_service.cpp.

56 {
57 client = srv_client;
58 }

References client.

Member Data Documentation

◆ client

carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory> intersection_transit_maneuvering::Servicer::client
private

Definition at line 58 of file itm_service.hpp.

Referenced by call(), and set_client().


The documentation for this class was generated from the following files: