18#include <carma_planning_msgs/msg/maneuver_plan.hpp>
19#include <carma_planning_msgs/srv/plan_maneuvers.hpp>
21#include <rclcpp/rclcpp.hpp>
29 if (!
planning_in_progress_ &&
nh_->get_current_state().id() != lifecycle_msgs::msg::State::TRANSITION_STATE_SHUTTINGDOWN)
33 switch (
sm_->get_state())
36 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"Arbitrator spinning in INITIAL state.");
40 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"Arbitrator spinning in PLANNING state.");
44 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"Arbitrator spinning in WAITING state.");
48 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"Arbitrator spinning in PAUSED state.");
52 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"Arbitrator shutting down after being commanded to shutdown!");
57 throw std::invalid_argument(
"State machine attempting to process an illegal state value");
71 case carma_planning_msgs::msg::GuidanceState::STARTUP:
74 case carma_planning_msgs::msg::GuidanceState::DRIVERS_READY:
77 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"Received notice that guidance has been restarted, pausing arbitrator.");
85 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"Received notice that guidance has been engaged!");
93 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"Received notice that guidance has been disengaged, pausing arbitrator.");
97 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"Received notice that guidance has been shutdown, shutting down arbitrator.");
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);
117 std::this_thread::sleep_for(std::chrono::milliseconds(100));
122 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"Arbitrator beginning planning process!");
123 rclcpp::Time planning_process_start =
nh_->get_clock()->now();
127 if (!plan.maneuvers.empty())
131 rclcpp::Duration plan_duration = plan_end_time - plan_start_time;
135 RCLCPP_WARN_STREAM(
nh_->get_logger(),
"Arbitrator is unable to generate a plan with minimum plan duration requirement!");
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");
145 RCLCPP_WARN_STREAM(
nh_->get_logger(),
"Arbitrator was unable to generate a plan!");
155 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"Arbitrator transitioning from WAITING to PLANNING state.");
161 std::this_thread::sleep_for(std::chrono::milliseconds(100));
166 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"Arbitrator shutting down...");
174 tf_ =
tf2_buffer_.lookupTransform(
"map",
"vehicle_front", rclcpp::Time(0), rclcpp::Duration(1.0, 0));
178 catch (
const tf2::TransformException &ex)
180 RCLCPP_WARN_STREAM(
nh_->get_logger(), ex.what());
187 if (
wm_->getRoute()) {
193 if (lanelets.empty()) {
195 RCLCPP_WARN_STREAM(
nh_->get_logger(),
"Vehicle is not in a lanelet.");
void planning_state()
Function to be called when the Arbitrator begins planning.
bool planning_in_progress_
tf2::Stamped< tf2::Transform > bumper_transform_
rclcpp::Time next_planning_process_start_
void shutdown_state()
Function to be executed when the Arbitrator is to clean up and shutdown.
void paused_state()
Function to be executed when the Arbitrator is not planning but also not awaiting a new plan cycle.
void initial_state()
Function to be executed during the initial state of the Arbitrator.
rclcpp::Duration min_plan_duration_
carma_ros2_utils::PubPtr< carma_planning_msgs::msg::ManeuverPlan > final_plan_pub_
std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > nh_
void twist_cb(geometry_msgs::msg::TwistStamped::UniquePtr msg)
Callback for the twist subscriber, which will store latest twist locally.
tf2_ros::Buffer tf2_buffer_
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::GuidanceState > guidance_state_sub_
void waiting_state()
Function to be executed when the Arbitrator has finished planning and is awaiting another planning cy...
carma_wm::WorldModelConstPtr wm_
rclcpp::Duration time_between_plans_
std::shared_ptr< PlanningStrategy > planning_strategy_
void initializeBumperTransformLookup()
Initialize transform Lookup from front bumper to map.
std::unique_ptr< tf2_ros::TransformListener > tf2_listener_
void run()
Begin the operation of the arbitrator.
VehicleState vehicle_state_
geometry_msgs::msg::TransformStamped tf_
void bumper_pose_cb()
Callback for the front bumper pose transform.
void guidance_state_cb(carma_planning_msgs::msg::GuidanceState::UniquePtr msg)
Callback for receiving Guidance state machine updates.
std::shared_ptr< ArbitratorStateMachine > sm_
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.
@ SYSTEM_STARTUP_COMPLETE
@ SYSTEM_SHUTDOWN_INITIATED