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

#include <port_drayage_plugin.hpp>

Inheritance diagram for port_drayage_plugin::PortDrayagePlugin:
Inheritance graph
Collaboration diagram for port_drayage_plugin::PortDrayagePlugin:
Collaboration graph

Public Member Functions

 PortDrayagePlugin (const rclcpp::NodeOptions &)
 PortDrayagePlugin constructor. More...
 
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. More...
 
void publishMobilityOperation (const carma_v2x_msgs::msg::MobilityOperation &msg)
 Publishes a Mobility Operation message to the outgoing mobility operation topic. More...
 
void publishUIInstructions (const carma_msgs::msg::UIInstructions &msg)
 Publishes a UI Instructions message to the outgoing UI Instructions topic. More...
 
rcl_interfaces::msg::SetParametersResult parameter_update_callback (const std::vector< rclcpp::Parameter > &parameters)
 Callback for dynamic parameter updates. More...
 
carma_ros2_utils::CallbackReturn handle_on_configure (const rclcpp_lifecycle::State &prev_state)
 

Private Attributes

carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseStamped > pose_subscriber_
 
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::MobilityOperation > inbound_mobility_operation_subscriber_
 
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::GuidanceState > guidance_state_subscriber_
 
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::RouteEvent > route_event_subscriber_
 
carma_ros2_utils::SubPtr< std_msgs::msg::String > georeference_subscriber_
 
carma_ros2_utils::PubPtr< carma_v2x_msgs::msg::MobilityOperation > outbound_mobility_operations_publisher_
 
carma_ros2_utils::PubPtr< carma_msgs::msg::UIInstructions > ui_instructions_publisher_
 
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::SetActiveRoute > set_active_route_client_
 
Config config_
 
PortDrayageWorker pdw_
 

Detailed Description

Primary Port Drayage Plugin implementation class. Split into this class primarily concerned with the handling of ROS message processing and the PortDrayageWorker class responsible for handling the core business logic of the Port Drayage functionality.

Definition at line 43 of file port_drayage_plugin.hpp.

Constructor & Destructor Documentation

◆ PortDrayagePlugin()

port_drayage_plugin::PortDrayagePlugin::PortDrayagePlugin ( const rclcpp::NodeOptions &  options)
explicit

PortDrayagePlugin constructor.

Definition at line 22 of file port_drayage_plugin.cpp.

23 : carma_ros2_utils::CarmaLifecycleNode(options),
24 pdw_(get_node_logging_interface(), get_clock(),
25 std::bind(&PortDrayagePlugin::publishMobilityOperation, this, std_ph::_1),
26 std::bind(&PortDrayagePlugin::publishUIInstructions, this, std_ph::_1),
27 std::bind(&PortDrayagePlugin::callSetActiveRouteClient, this, std_ph::_1))
28 {
29 // Create initial config
30 config_ = Config();
31
32 // Declare parameters
33 config_.cmv_id = declare_parameter<std::string>("vehicle_id", config_.cmv_id);
34 config_.cargo_id = declare_parameter<std::string>("cargo_id", config_.cargo_id);
35 config_.enable_port_drayage = declare_parameter<bool>("enable_port_drayage", config_.enable_port_drayage);
36 config_.starting_at_staging_area = declare_parameter<bool>("starting_at_staging_area", config_.starting_at_staging_area);
37 }
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.
void publishMobilityOperation(const carma_v2x_msgs::msg::MobilityOperation &msg)
Publishes a Mobility Operation message to the outgoing mobility operation topic.
void publishUIInstructions(const carma_msgs::msg::UIInstructions &msg)
Publishes a UI Instructions message to the outgoing UI Instructions topic.

References port_drayage_plugin::Config::cargo_id, port_drayage_plugin::Config::cmv_id, config_, port_drayage_plugin::Config::enable_port_drayage, and port_drayage_plugin::Config::starting_at_staging_area.

Member Function Documentation

◆ callSetActiveRouteClient()

bool port_drayage_plugin::PortDrayagePlugin::callSetActiveRouteClient ( std::shared_ptr< carma_planning_msgs::srv::SetActiveRoute::Request >  req)

Calls the /guidance/set_active_route service client to set an active route.

Parameters
reqThe service request being used to call the service client
Returns
If the service client call was successful and no errors occurred while setting the new active route

Definition at line 110 of file port_drayage_plugin.cpp.

111 {
112 // Send request to set_active_route service
113 auto route_result = set_active_route_client_->async_send_request(req);
114
115 // Wait for response from service call
116 auto future_status = route_result.wait_for(std::chrono::milliseconds(100));
117
118 if (future_status == std::future_status::ready) {
119 if(route_result.get()->error_status == carma_planning_msgs::srv::SetActiveRoute::Response::NO_ERROR){
120 RCLCPP_DEBUG_STREAM(get_logger(), "Route Generation succeeded for Set Active Route service call.");
121 return true;
122 }
123 else{
124 RCLCPP_DEBUG_STREAM(get_logger(), "Route Generation failed for Set Active Route service call.");
125 return false;
126 }
127 }
128 else {
129 // No response was received after making the service call
130 RCLCPP_DEBUG_STREAM(get_logger(), "Set Active Route service call was not successful.");
131 return false;
132 }
133
134 }
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::SetActiveRoute > set_active_route_client_

References set_active_route_client_.

◆ handle_on_configure()

carma_ros2_utils::CallbackReturn port_drayage_plugin::PortDrayagePlugin::handle_on_configure ( const rclcpp_lifecycle::State &  prev_state)

Definition at line 63 of file port_drayage_plugin.cpp.

64 {
65 RCLCPP_INFO_STREAM(get_logger(), "port_drayage_plugin trying to configure");
66
67 // Reset config
68 config_ = Config();
69
70 // Load parameters
71 get_parameter<std::string>("vehicle_id", config_.cmv_id);
72 get_parameter<std::string>("cargo_id", config_.cargo_id);
73 get_parameter<bool>("enable_port_drayage", config_.enable_port_drayage);
74 get_parameter<bool>("starting_at_staging_area", config_.starting_at_staging_area);
75
76 RCLCPP_INFO_STREAM(get_logger(), "Loaded params: " << config_);
77
78 // Register runtime parameter update callback
79 add_on_set_parameters_callback(std::bind(&PortDrayagePlugin::parameter_update_callback, this, std_ph::_1));
80
81 // Setup subscribers
82 pose_subscriber_ = create_subscription<geometry_msgs::msg::PoseStamped>("current_pose", 5,
83 std::bind(&PortDrayageWorker::onNewPose, &pdw_, std_ph::_1));
84 inbound_mobility_operation_subscriber_ = create_subscription<carma_v2x_msgs::msg::MobilityOperation>("incoming_mobility_operation", 5,
85 std::bind(&PortDrayageWorker::onInboundMobilityOperation, &pdw_, std_ph::_1));
86 guidance_state_subscriber_ = create_subscription<carma_planning_msgs::msg::GuidanceState> ("guidance_state", 5,
87 std::bind(&PortDrayageWorker::onGuidanceState, &pdw_, std_ph::_1));
88 route_event_subscriber_ = create_subscription<carma_planning_msgs::msg::RouteEvent>("route_event", 5,
89 std::bind(&PortDrayageWorker::onRouteEvent, &pdw_, std_ph::_1));
90 georeference_subscriber_ = create_subscription<std_msgs::msg::String>("georeference", 1,
91 std::bind(&PortDrayageWorker::onNewGeoreference, &pdw_, std_ph::_1));
92
93 // Setup publishers
94 outbound_mobility_operations_publisher_ = create_publisher<carma_v2x_msgs::msg::MobilityOperation>("outgoing_mobility_operation", 5);
95 ui_instructions_publisher_ = create_publisher<carma_msgs::msg::UIInstructions>("ui_instructions", 5);
96
97 // Setup service clients
98 set_active_route_client_ = create_client<carma_planning_msgs::srv::SetActiveRoute>("set_active_route");
99
100 // Set PortDrayageWorker variables
105
106 // Return success if everything initialized successfully
107 return CallbackReturn::SUCCESS;
108 }
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::SubPtr< carma_planning_msgs::msg::GuidanceState > guidance_state_subscriber_
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::MobilityOperation > inbound_mobility_operation_subscriber_
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::RouteEvent > route_event_subscriber_
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)
Callback for dynamic parameter updates.
void setVehicleID(const std::string &cmv_id)
Setter function to set this object's cmv_id_ string.
void setStartingAtStagingAreaFlag(bool starting_at_staging_area)
Setter function to set this object's starting_at_staging_area flag.
void onRouteEvent(const carma_planning_msgs::msg::RouteEvent::UniquePtr msg)
Callback to process each Route Event.
void setEnablePortDrayageFlag(bool enable_port_drayage)
Setter function to set this object's enable_port_drayage flag.
void onNewPose(geometry_msgs::msg::PoseStamped::UniquePtr msg)
Callback for the pose subscriber. The pose will be converted into lat/lon and stored locally.
void onGuidanceState(const carma_planning_msgs::msg::GuidanceState::UniquePtr msg)
Callback to process the current status of the guidance state machine.
void onInboundMobilityOperation(carma_v2x_msgs::msg::MobilityOperation::UniquePtr msg)
Callback to process a received MobilityOperation message.
void setCargoID(const std::string &cargo_id)
Setter function to set this object's cargo_id_ string.
void onNewGeoreference(std_msgs::msg::String::UniquePtr msg)
Callback for map projection string to define lat/lon <--> map conversion.

References port_drayage_plugin::Config::cargo_id, port_drayage_plugin::Config::cmv_id, config_, port_drayage_plugin::Config::enable_port_drayage, georeference_subscriber_, guidance_state_subscriber_, inbound_mobility_operation_subscriber_, port_drayage_plugin::PortDrayageWorker::onGuidanceState(), port_drayage_plugin::PortDrayageWorker::onInboundMobilityOperation(), port_drayage_plugin::PortDrayageWorker::onNewGeoreference(), port_drayage_plugin::PortDrayageWorker::onNewPose(), port_drayage_plugin::PortDrayageWorker::onRouteEvent(), outbound_mobility_operations_publisher_, parameter_update_callback(), pdw_, pose_subscriber_, route_event_subscriber_, set_active_route_client_, port_drayage_plugin::PortDrayageWorker::setCargoID(), port_drayage_plugin::PortDrayageWorker::setEnablePortDrayageFlag(), port_drayage_plugin::PortDrayageWorker::setStartingAtStagingAreaFlag(), port_drayage_plugin::PortDrayageWorker::setVehicleID(), port_drayage_plugin::Config::starting_at_staging_area, and ui_instructions_publisher_.

Here is the call graph for this function:

◆ parameter_update_callback()

rcl_interfaces::msg::SetParametersResult port_drayage_plugin::PortDrayagePlugin::parameter_update_callback ( const std::vector< rclcpp::Parameter > &  parameters)

Callback for dynamic parameter updates.

Definition at line 39 of file port_drayage_plugin.cpp.

40 {
41 auto error = update_params<std::string>({
42 {"vehicle_id", config_.cmv_id},
43 {"cargo_id", config_.cargo_id}}, parameters);
44 auto error_2 = update_params<bool>({
45 {"enable_port_drayage", config_.enable_port_drayage},
46 {"starting_at_staging_area", config_.starting_at_staging_area}}, parameters);
47
48 rcl_interfaces::msg::SetParametersResult result;
49
50 result.successful = !error && !error_2;
51
52 if (result.successful) {
53 // Set PortDrayageWorker parameters
58 }
59
60 return result;
61 }

References port_drayage_plugin::Config::cargo_id, port_drayage_plugin::Config::cmv_id, config_, port_drayage_plugin::Config::enable_port_drayage, pdw_, port_drayage_plugin::PortDrayageWorker::setCargoID(), port_drayage_plugin::PortDrayageWorker::setEnablePortDrayageFlag(), port_drayage_plugin::PortDrayageWorker::setStartingAtStagingAreaFlag(), port_drayage_plugin::PortDrayageWorker::setVehicleID(), and port_drayage_plugin::Config::starting_at_staging_area.

Referenced by handle_on_configure().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ publishMobilityOperation()

void port_drayage_plugin::PortDrayagePlugin::publishMobilityOperation ( const carma_v2x_msgs::msg::MobilityOperation &  msg)

Publishes a Mobility Operation message to the outgoing mobility operation topic.

Parameters
msgThe Mobility Operation message to be published

Definition at line 136 of file port_drayage_plugin.cpp.

137 {
139 }

References outbound_mobility_operations_publisher_.

◆ publishUIInstructions()

void port_drayage_plugin::PortDrayagePlugin::publishUIInstructions ( const carma_msgs::msg::UIInstructions &  msg)

Publishes a UI Instructions message to the outgoing UI Instructions topic.

Parameters
msgThe UI Instructions message to be published

Definition at line 141 of file port_drayage_plugin.cpp.

142 {
143 ui_instructions_publisher_->publish(msg);
144 }

References ui_instructions_publisher_.

Member Data Documentation

◆ config_

Config port_drayage_plugin::PortDrayagePlugin::config_
private

◆ georeference_subscriber_

carma_ros2_utils::SubPtr<std_msgs::msg::String> port_drayage_plugin::PortDrayagePlugin::georeference_subscriber_
private

Definition at line 52 of file port_drayage_plugin.hpp.

Referenced by handle_on_configure().

◆ guidance_state_subscriber_

carma_ros2_utils::SubPtr<carma_planning_msgs::msg::GuidanceState> port_drayage_plugin::PortDrayagePlugin::guidance_state_subscriber_
private

Definition at line 50 of file port_drayage_plugin.hpp.

Referenced by handle_on_configure().

◆ inbound_mobility_operation_subscriber_

carma_ros2_utils::SubPtr<carma_v2x_msgs::msg::MobilityOperation> port_drayage_plugin::PortDrayagePlugin::inbound_mobility_operation_subscriber_
private

Definition at line 49 of file port_drayage_plugin.hpp.

Referenced by handle_on_configure().

◆ outbound_mobility_operations_publisher_

carma_ros2_utils::PubPtr<carma_v2x_msgs::msg::MobilityOperation> port_drayage_plugin::PortDrayagePlugin::outbound_mobility_operations_publisher_
private

Definition at line 55 of file port_drayage_plugin.hpp.

Referenced by handle_on_configure(), and publishMobilityOperation().

◆ pdw_

PortDrayageWorker port_drayage_plugin::PortDrayagePlugin::pdw_
private

Definition at line 65 of file port_drayage_plugin.hpp.

Referenced by handle_on_configure(), and parameter_update_callback().

◆ pose_subscriber_

carma_ros2_utils::SubPtr<geometry_msgs::msg::PoseStamped> port_drayage_plugin::PortDrayagePlugin::pose_subscriber_
private

Definition at line 48 of file port_drayage_plugin.hpp.

Referenced by handle_on_configure().

◆ route_event_subscriber_

carma_ros2_utils::SubPtr<carma_planning_msgs::msg::RouteEvent> port_drayage_plugin::PortDrayagePlugin::route_event_subscriber_
private

Definition at line 51 of file port_drayage_plugin.hpp.

Referenced by handle_on_configure().

◆ set_active_route_client_

carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::SetActiveRoute> port_drayage_plugin::PortDrayagePlugin::set_active_route_client_
private

Definition at line 59 of file port_drayage_plugin.hpp.

Referenced by callSetActiveRouteClient(), and handle_on_configure().

◆ ui_instructions_publisher_

carma_ros2_utils::PubPtr<carma_msgs::msg::UIInstructions> port_drayage_plugin::PortDrayagePlugin::ui_instructions_publisher_
private

Definition at line 56 of file port_drayage_plugin.hpp.

Referenced by handle_on_configure(), and publishUIInstructions().


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