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.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2022 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
16
17#include "arbitrator.hpp"
18#include <carma_planning_msgs/msg/maneuver_plan.hpp>
19#include <carma_planning_msgs/srv/plan_maneuvers.hpp>
20#include "arbitrator_utils.hpp"
21#include <rclcpp/rclcpp.hpp>
22#include <exception>
23#include <cstdlib>
24
25namespace arbitrator
26{
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 }
66
67 void Arbitrator::guidance_state_cb(carma_planning_msgs::msg::GuidanceState::UniquePtr msg)
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 }
104
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 }
119
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 }
152
154 {
155 RCLCPP_INFO_STREAM(nh_->get_logger(), "Arbitrator transitioning from WAITING to PLANNING state.");
157 }
158
160 {
161 std::this_thread::sleep_for(std::chrono::milliseconds(100));
162 }
163
165 {
166 RCLCPP_INFO_STREAM(nh_->get_logger(), "Arbitrator shutting down...");
167 rclcpp::shutdown(); // Will stop upper level spin and shutdown node
168 }
169
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 }
205
206 void Arbitrator::twist_cb(geometry_msgs::msg::TwistStamped::UniquePtr msg)
207 {
208 vehicle_state_.velocity = msg->twist.linear.x;
209 }
210
212 {
213 tf2_listener_.reset(new tf2_ros::TransformListener(tf2_buffer_));
214 tf2_buffer_.setUsingDedicatedThread(true);
215 }
216}
void planning_state()
Function to be called when the Arbitrator begins planning.
Definition: arbitrator.cpp:120
tf2::Stamped< tf2::Transform > bumper_transform_
Definition: arbitrator.hpp:152
rclcpp::Time next_planning_process_start_
Definition: arbitrator.hpp:141
void shutdown_state()
Function to be executed when the Arbitrator is to clean up and shutdown.
Definition: arbitrator.cpp:164
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
rclcpp::Duration min_plan_duration_
Definition: arbitrator.hpp:139
carma_ros2_utils::PubPtr< carma_planning_msgs::msg::ManeuverPlan > final_plan_pub_
Definition: arbitrator.hpp:136
std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > nh_
Definition: arbitrator.hpp:138
void twist_cb(geometry_msgs::msg::TwistStamped::UniquePtr msg)
Callback for the twist subscriber, which will store latest twist locally.
Definition: arbitrator.cpp:206
tf2_ros::Buffer tf2_buffer_
Definition: arbitrator.hpp:149
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::GuidanceState > guidance_state_sub_
Definition: arbitrator.hpp:137
void waiting_state()
Function to be executed when the Arbitrator has finished planning and is awaiting another planning cy...
Definition: arbitrator.cpp:153
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
void initializeBumperTransformLookup()
Initialize transform Lookup from front bumper to map.
Definition: arbitrator.cpp:211
std::unique_ptr< tf2_ros::TransformListener > tf2_listener_
Definition: arbitrator.hpp:150
void run()
Begin the operation of the arbitrator.
Definition: arbitrator.cpp:27
VehicleState vehicle_state_
Definition: arbitrator.hpp:133
geometry_msgs::msg::TransformStamped tf_
Definition: arbitrator.hpp:147
void bumper_pose_cb()
Callback for the front bumper pose transform.
Definition: arbitrator.cpp:170
void guidance_state_cb(carma_planning_msgs::msg::GuidanceState::UniquePtr msg)
Callback for receiving Guidance state machine updates.
Definition: arbitrator.cpp:67
std::shared_ptr< ArbitratorStateMachine > sm_
Definition: arbitrator.hpp:135
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.