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.
arbitrator::Arbitrator Class Reference

#include <arbitrator.hpp>

Collaboration diagram for arbitrator::Arbitrator:
Collaboration graph

Public Member Functions

 Arbitrator (std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > nh, std::shared_ptr< ArbitratorStateMachine > sm, std::shared_ptr< CapabilitiesInterface > ci, std::shared_ptr< PlanningStrategy > planning_strategy, rclcpp::Duration min_plan_duration, double planning_period, carma_wm::WorldModelConstPtr wm)
 Constructor for arbitrator class taking in dependencies via dependency injection. More...
 
void run ()
 Begin the operation of the arbitrator. More...
 
void twist_cb (geometry_msgs::msg::TwistStamped::UniquePtr msg)
 Callback for the twist subscriber, which will store latest twist locally. More...
 
void bumper_pose_cb ()
 Callback for the front bumper pose transform. More...
 
void initializeBumperTransformLookup ()
 Initialize transform Lookup from front bumper to map. More...
 

Protected Member Functions

void initial_state ()
 Function to be executed during the initial state of the Arbitrator. More...
 
void planning_state ()
 Function to be called when the Arbitrator begins planning. More...
 
void waiting_state ()
 Function to be executed when the Arbitrator has finished planning and is awaiting another planning cycle. More...
 
void paused_state ()
 Function to be executed when the Arbitrator is not planning but also not awaiting a new plan cycle. More...
 
void shutdown_state ()
 Function to be executed when the Arbitrator is to clean up and shutdown. More...
 
void guidance_state_cb (carma_planning_msgs::msg::GuidanceState::UniquePtr msg)
 Callback for receiving Guidance state machine updates. More...
 

Private Attributes

VehicleState vehicle_state_
 
std::shared_ptr< ArbitratorStateMachinesm_
 
carma_ros2_utils::PubPtr< carma_planning_msgs::msg::ManeuverPlan > final_plan_pub_
 
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::GuidanceState > guidance_state_sub_
 
std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > nh_
 
rclcpp::Duration min_plan_duration_
 
rclcpp::Duration time_between_plans_
 
rclcpp::Time next_planning_process_start_
 
std::shared_ptr< CapabilitiesInterfacecapabilities_interface_
 
std::shared_ptr< PlanningStrategyplanning_strategy_
 
bool initialized_
 
carma_wm::WorldModelConstPtr wm_
 
geometry_msgs::msg::TransformStamped tf_
 
tf2_ros::Buffer tf2_buffer_
 
std::unique_ptr< tf2_ros::TransformListener > tf2_listener_
 
tf2::Stamped< tf2::Transform > bumper_transform_
 
bool planning_in_progress_ = false
 

Detailed Description

Primary work class for the Arbitrator package

Governs the interactions of plugins during the maneuver planning phase of the CARMA planning process. Utilizes a generic planning interface to allow for reconfiguration with other paradigms in the future.

Definition at line 44 of file arbitrator.hpp.

Constructor & Destructor Documentation

◆ Arbitrator()

arbitrator::Arbitrator::Arbitrator ( std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode >  nh,
std::shared_ptr< ArbitratorStateMachine sm,
std::shared_ptr< CapabilitiesInterface ci,
std::shared_ptr< PlanningStrategy planning_strategy,
rclcpp::Duration  min_plan_duration,
double  planning_period,
carma_wm::WorldModelConstPtr  wm 
)
inline

Constructor for arbitrator class taking in dependencies via dependency injection.

Parameters
nhA CarmaLifecycleNode node pointer
smAn ArbitratorStateMachine instance for regulating the states of the Arbitrator
ciA CapabilitiesInterface for querying plugins
planning_strategyA planning strategy implementation for generating plans
min_plan_durationThe minimum acceptable length of a plan
planning_frequencyThe frequency at which to generate high-level plans when engaged
wmpointer to an inialized world model.

Definition at line 57 of file arbitrator.hpp.

63 :
64 sm_(sm),
65 nh_(nh),
66 min_plan_duration_(min_plan_duration),
67 time_between_plans_(planning_period),
69 planning_strategy_(planning_strategy),
70 initialized_(false),
71 wm_(wm),
72 tf2_buffer_(nh_->get_clock()) {};
rclcpp::Duration min_plan_duration_
Definition: arbitrator.hpp:139
std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > nh_
Definition: arbitrator.hpp:138
tf2_ros::Buffer tf2_buffer_
Definition: arbitrator.hpp:149
carma_wm::WorldModelConstPtr wm_
Definition: arbitrator.hpp:145
rclcpp::Duration time_between_plans_
Definition: arbitrator.hpp:140
std::shared_ptr< PlanningStrategy > planning_strategy_
Definition: arbitrator.hpp:143
std::shared_ptr< CapabilitiesInterface > capabilities_interface_
Definition: arbitrator.hpp:142
std::shared_ptr< ArbitratorStateMachine > sm_
Definition: arbitrator.hpp:135

Member Function Documentation

◆ bumper_pose_cb()

void arbitrator::Arbitrator::bumper_pose_cb ( )

Callback for the front bumper pose transform.

Definition at line 170 of file arbitrator.cpp.

171 {
172 try
173 {
174 tf_ = tf2_buffer_.lookupTransform("map", "vehicle_front", rclcpp::Time(0), rclcpp::Duration(1.0, 0)); //save to local copy of transform 1 sec timeout
175 tf2::fromMsg(tf_, bumper_transform_);
176 vehicle_state_.stamp = tf_.header.stamp;
177 }
178 catch (const tf2::TransformException &ex)
179 {
180 RCLCPP_WARN_STREAM(nh_->get_logger(), ex.what());
181 }
182
183 vehicle_state_.x = bumper_transform_.getOrigin().getX();
184 vehicle_state_.y = bumper_transform_.getOrigin().getY();
185
186 // If the route is available then set the downtrack and lane id
187 if (wm_->getRoute()) {
188
189 vehicle_state_.downtrack = wm_->routeTrackPos( { vehicle_state_.x, vehicle_state_.y } ).downtrack;
190
191 auto lanelets = wm_->getLaneletsBetween(vehicle_state_.downtrack, vehicle_state_.downtrack, true);
192
193 if (lanelets.empty()) {
194
195 RCLCPP_WARN_STREAM(nh_->get_logger(), "Vehicle is not in a lanelet.");
196 vehicle_state_.lane_id = lanelet::InvalId;
197
198 } else {
199
200 vehicle_state_.lane_id = lanelets[0].id();
201 }
202 }
203
204 }
tf2::Stamped< tf2::Transform > bumper_transform_
Definition: arbitrator.hpp:152
VehicleState vehicle_state_
Definition: arbitrator.hpp:133
geometry_msgs::msg::TransformStamped tf_
Definition: arbitrator.hpp:147

References bumper_transform_, arbitrator::VehicleState::downtrack, arbitrator::VehicleState::lane_id, nh_, arbitrator::VehicleState::stamp, tf2_buffer_, tf_, vehicle_state_, wm_, arbitrator::VehicleState::x, and arbitrator::VehicleState::y.

◆ guidance_state_cb()

void arbitrator::Arbitrator::guidance_state_cb ( carma_planning_msgs::msg::GuidanceState::UniquePtr  msg)
protected

Callback for receiving Guidance state machine updates.

Parameters
msgThe new GuidanceState message

Definition at line 67 of file arbitrator.cpp.

68 {
69 switch (msg->state)
70 {
71 case carma_planning_msgs::msg::GuidanceState::STARTUP:
72 // NO-OP
73 break;
74 case carma_planning_msgs::msg::GuidanceState::DRIVERS_READY:
75 if(sm_->get_state() == ArbitratorState::PLANNING || sm_->get_state() == ArbitratorState::WAITING)
76 {
77 RCLCPP_INFO_STREAM(nh_->get_logger(), "Received notice that guidance has been restarted, pausing arbitrator.");
79 }
80 break;
82 // NO-OP
83 break;
85 RCLCPP_INFO_STREAM(nh_->get_logger(), "Received notice that guidance has been engaged!");
86 if (sm_->get_state() == ArbitratorState::INITIAL) {
88 } else if (sm_->get_state() == ArbitratorState::PAUSED) {
90 }
91 break;
93 RCLCPP_INFO_STREAM(nh_->get_logger(), "Received notice that guidance has been disengaged, pausing arbitrator.");
95 break;
97 RCLCPP_INFO_STREAM(nh_->get_logger(), "Received notice that guidance has been shutdown, shutting down arbitrator.");
99 break;
100 default:
101 break;
102 }
103 }

References lightbar_manager::ACTIVE, arbitrator::ARBITRATOR_PAUSED, arbitrator::ARBITRATOR_RESUMED, lightbar_manager::ENGAGED, port_drayage_plugin::INACTIVE, arbitrator::INITIAL, nh_, arbitrator::PAUSED, arbitrator::PLANNING, arbitrator::SHUTDOWN, sm_, arbitrator::SYSTEM_SHUTDOWN_INITIATED, arbitrator::SYSTEM_STARTUP_COMPLETE, and arbitrator::WAITING.

Referenced by initial_state().

Here is the caller graph for this function:

◆ initial_state()

void arbitrator::Arbitrator::initial_state ( )
protected

Function to be executed during the initial state of the Arbitrator.

Definition at line 105 of file arbitrator.cpp.

106 {
107 if(!initialized_)
108 {
109 RCLCPP_INFO_STREAM(nh_->get_logger(), "Arbitrator initializing on first initial state spin...");
110 final_plan_pub_ = nh_->create_publisher<carma_planning_msgs::msg::ManeuverPlan>("final_maneuver_plan", 5);
111 guidance_state_sub_ = nh_->create_subscription<carma_planning_msgs::msg::GuidanceState>("guidance_state", 5, std::bind(&Arbitrator::guidance_state_cb, this, std::placeholders::_1));
112 final_plan_pub_->on_activate();
113
114 initialized_ = true;
115 }
116
117 std::this_thread::sleep_for(std::chrono::milliseconds(100));
118 }
carma_ros2_utils::PubPtr< carma_planning_msgs::msg::ManeuverPlan > final_plan_pub_
Definition: arbitrator.hpp:136
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::GuidanceState > guidance_state_sub_
Definition: arbitrator.hpp:137
void guidance_state_cb(carma_planning_msgs::msg::GuidanceState::UniquePtr msg)
Callback for receiving Guidance state machine updates.
Definition: arbitrator.cpp:67

References final_plan_pub_, guidance_state_cb(), guidance_state_sub_, initialized_, and nh_.

Referenced by run().

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

◆ initializeBumperTransformLookup()

void arbitrator::Arbitrator::initializeBumperTransformLookup ( )

Initialize transform Lookup from front bumper to map.

Definition at line 211 of file arbitrator.cpp.

212 {
213 tf2_listener_.reset(new tf2_ros::TransformListener(tf2_buffer_));
214 tf2_buffer_.setUsingDedicatedThread(true);
215 }
std::unique_ptr< tf2_ros::TransformListener > tf2_listener_
Definition: arbitrator.hpp:150

References tf2_buffer_, and tf2_listener_.

◆ paused_state()

void arbitrator::Arbitrator::paused_state ( )
protected

Function to be executed when the Arbitrator is not planning but also not awaiting a new plan cycle.

Definition at line 159 of file arbitrator.cpp.

160 {
161 std::this_thread::sleep_for(std::chrono::milliseconds(100));
162 }

Referenced by run().

Here is the caller graph for this function:

◆ planning_state()

void arbitrator::Arbitrator::planning_state ( )
protected

Function to be called when the Arbitrator begins planning.

Definition at line 120 of file arbitrator.cpp.

121 {
122 RCLCPP_INFO_STREAM(nh_->get_logger(), "Arbitrator beginning planning process!");
123 rclcpp::Time planning_process_start = nh_->get_clock()->now();
124
125 carma_planning_msgs::msg::ManeuverPlan plan = planning_strategy_->generate_plan(vehicle_state_);
126
127 if (!plan.maneuvers.empty())
128 {
129 rclcpp::Time plan_end_time = arbitrator_utils::get_plan_end_time(plan);
130 rclcpp::Time plan_start_time = arbitrator_utils::get_plan_start_time(plan);
131 rclcpp::Duration plan_duration = plan_end_time - plan_start_time;
132
133 if (plan_duration < min_plan_duration_)
134 {
135 RCLCPP_WARN_STREAM(nh_->get_logger(), "Arbitrator is unable to generate a plan with minimum plan duration requirement!");
136 }
137 else
138 {
139 RCLCPP_INFO_STREAM(nh_->get_logger(), "Arbitrator is publishing plan " << std::string(plan.maneuver_plan_id) << " of duration " << plan_duration.seconds() << " as current maneuver plan");
140 }
141 final_plan_pub_->publish(plan);
142 }
143 else
144 {
145 RCLCPP_WARN_STREAM(nh_->get_logger(), "Arbitrator was unable to generate a plan!");
146 }
147
148 next_planning_process_start_ = planning_process_start + time_between_plans_;
149
151 }
rclcpp::Time next_planning_process_start_
Definition: arbitrator.hpp:141
rclcpp::Time get_plan_start_time(const carma_planning_msgs::msg::ManeuverPlan &)
Get the start time of the first maneuver in the plan.
rclcpp::Time get_plan_end_time(const carma_planning_msgs::msg::ManeuverPlan &)
Get the end time of the first maneuver in the plan.

References final_plan_pub_, arbitrator_utils::get_plan_end_time(), arbitrator_utils::get_plan_start_time(), min_plan_duration_, next_planning_process_start_, nh_, arbitrator::PLANNING_COMPLETE, planning_strategy_, sm_, time_between_plans_, and vehicle_state_.

Referenced by run().

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

◆ run()

void arbitrator::Arbitrator::run ( )

Begin the operation of the arbitrator.

Loops internally via rclcpp::Duration sleeps and spins

Definition at line 27 of file arbitrator.cpp.

28 {
29 if (!planning_in_progress_ && nh_->get_current_state().id() != lifecycle_msgs::msg::State::TRANSITION_STATE_SHUTTINGDOWN)
30 {
32
33 switch (sm_->get_state())
34 {
35 case INITIAL:
36 RCLCPP_INFO_STREAM(nh_->get_logger(), "Arbitrator spinning in INITIAL state.");
38 break;
39 case PLANNING:
40 RCLCPP_INFO_STREAM(nh_->get_logger(), "Arbitrator spinning in PLANNING state.");
42 break;
43 case WAITING:
44 RCLCPP_INFO_STREAM(nh_->get_logger(), "Arbitrator spinning in WAITING state.");
46 break;
47 case PAUSED:
48 RCLCPP_INFO_STREAM(nh_->get_logger(), "Arbitrator spinning in PAUSED state.");
50 break;
51 case SHUTDOWN:
52 RCLCPP_INFO_STREAM(nh_->get_logger(), "Arbitrator shutting down after being commanded to shutdown!");
53 rclcpp::shutdown();
54 exit(0);
55 break;
56 default:
57 throw std::invalid_argument("State machine attempting to process an illegal state value");
58 }
59 }
60 else
61 {
62 return;
63 }
65 }
void planning_state()
Function to be called when the Arbitrator begins planning.
Definition: arbitrator.cpp:120
void paused_state()
Function to be executed when the Arbitrator is not planning but also not awaiting a new plan cycle.
Definition: arbitrator.cpp:159
void initial_state()
Function to be executed during the initial state of the Arbitrator.
Definition: arbitrator.cpp:105
void waiting_state()
Function to be executed when the Arbitrator has finished planning and is awaiting another planning cy...
Definition: arbitrator.cpp:153

References arbitrator::INITIAL, initial_state(), nh_, arbitrator::PAUSED, paused_state(), arbitrator::PLANNING, planning_in_progress_, planning_state(), arbitrator::SHUTDOWN, sm_, arbitrator::WAITING, and waiting_state().

Here is the call graph for this function:

◆ shutdown_state()

void arbitrator::Arbitrator::shutdown_state ( )
protected

Function to be executed when the Arbitrator is to clean up and shutdown.

Definition at line 164 of file arbitrator.cpp.

165 {
166 RCLCPP_INFO_STREAM(nh_->get_logger(), "Arbitrator shutting down...");
167 rclcpp::shutdown(); // Will stop upper level spin and shutdown node
168 }

References nh_.

◆ twist_cb()

void arbitrator::Arbitrator::twist_cb ( geometry_msgs::msg::TwistStamped::UniquePtr  msg)

Callback for the twist subscriber, which will store latest twist locally.

Parameters
msgLatest twist message

Definition at line 206 of file arbitrator.cpp.

207 {
208 vehicle_state_.velocity = msg->twist.linear.x;
209 }

References vehicle_state_, and arbitrator::VehicleState::velocity.

Referenced by arbitrator::ArbitratorNode::handle_on_configure().

Here is the caller graph for this function:

◆ waiting_state()

void arbitrator::Arbitrator::waiting_state ( )
protected

Function to be executed when the Arbitrator has finished planning and is awaiting another planning cycle.

Definition at line 153 of file arbitrator.cpp.

154 {
155 RCLCPP_INFO_STREAM(nh_->get_logger(), "Arbitrator transitioning from WAITING to PLANNING state.");
157 }

References nh_, arbitrator::PLANNING_TIMER_TRIGGER, and sm_.

Referenced by run().

Here is the caller graph for this function:

Member Data Documentation

◆ bumper_transform_

tf2::Stamped<tf2::Transform> arbitrator::Arbitrator::bumper_transform_
private

Definition at line 152 of file arbitrator.hpp.

Referenced by bumper_pose_cb().

◆ capabilities_interface_

std::shared_ptr<CapabilitiesInterface> arbitrator::Arbitrator::capabilities_interface_
private

Definition at line 142 of file arbitrator.hpp.

◆ final_plan_pub_

carma_ros2_utils::PubPtr<carma_planning_msgs::msg::ManeuverPlan> arbitrator::Arbitrator::final_plan_pub_
private

Definition at line 136 of file arbitrator.hpp.

Referenced by initial_state(), and planning_state().

◆ guidance_state_sub_

carma_ros2_utils::SubPtr<carma_planning_msgs::msg::GuidanceState> arbitrator::Arbitrator::guidance_state_sub_
private

Definition at line 137 of file arbitrator.hpp.

Referenced by initial_state().

◆ initialized_

bool arbitrator::Arbitrator::initialized_
private

Definition at line 144 of file arbitrator.hpp.

Referenced by initial_state().

◆ min_plan_duration_

rclcpp::Duration arbitrator::Arbitrator::min_plan_duration_
private

Definition at line 139 of file arbitrator.hpp.

Referenced by planning_state().

◆ next_planning_process_start_

rclcpp::Time arbitrator::Arbitrator::next_planning_process_start_
private

Definition at line 141 of file arbitrator.hpp.

Referenced by planning_state().

◆ nh_

std::shared_ptr<carma_ros2_utils::CarmaLifecycleNode> arbitrator::Arbitrator::nh_
private

◆ planning_in_progress_

bool arbitrator::Arbitrator::planning_in_progress_ = false
private

Definition at line 153 of file arbitrator.hpp.

Referenced by run().

◆ planning_strategy_

std::shared_ptr<PlanningStrategy> arbitrator::Arbitrator::planning_strategy_
private

Definition at line 143 of file arbitrator.hpp.

Referenced by planning_state().

◆ sm_

std::shared_ptr<ArbitratorStateMachine> arbitrator::Arbitrator::sm_
private

Definition at line 135 of file arbitrator.hpp.

Referenced by guidance_state_cb(), planning_state(), run(), and waiting_state().

◆ tf2_buffer_

tf2_ros::Buffer arbitrator::Arbitrator::tf2_buffer_
private

Definition at line 149 of file arbitrator.hpp.

Referenced by bumper_pose_cb(), and initializeBumperTransformLookup().

◆ tf2_listener_

std::unique_ptr<tf2_ros::TransformListener> arbitrator::Arbitrator::tf2_listener_
private

Definition at line 150 of file arbitrator.hpp.

Referenced by initializeBumperTransformLookup().

◆ tf_

geometry_msgs::msg::TransformStamped arbitrator::Arbitrator::tf_
private

Definition at line 147 of file arbitrator.hpp.

Referenced by bumper_pose_cb().

◆ time_between_plans_

rclcpp::Duration arbitrator::Arbitrator::time_between_plans_
private

Definition at line 140 of file arbitrator.hpp.

Referenced by planning_state().

◆ vehicle_state_

VehicleState arbitrator::Arbitrator::vehicle_state_
private

Definition at line 133 of file arbitrator.hpp.

Referenced by bumper_pose_cb(), planning_state(), and twist_cb().

◆ wm_

carma_wm::WorldModelConstPtr arbitrator::Arbitrator::wm_
private

Definition at line 145 of file arbitrator.hpp.

Referenced by bumper_pose_cb().


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