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.hpp
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#ifndef __ARBITRATOR_INCLUDE_ARBITRATOR_HPP__
18#define __ARBITRATOR_INCLUDE_ARBITRATOR_HPP__
19
20#include <rclcpp/rclcpp.hpp>
21#include <carma_ros2_utils/carma_lifecycle_node.hpp>
22#include <carma_planning_msgs/msg/guidance_state.hpp>
24#include <geometry_msgs/msg/pose_stamped.hpp>
25#include <geometry_msgs/msg/twist_stamped.hpp>
26#include <tf2_ros/transform_listener.h>
27#include <tf2/LinearMath/Transform.h>
28#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
29
30#include "vehicle_state.hpp"
32#include "planning_strategy.hpp"
34
35namespace arbitrator
36{
45 {
46 public:
57 Arbitrator(std::shared_ptr<carma_ros2_utils::CarmaLifecycleNode> nh,
58 std::shared_ptr<ArbitratorStateMachine> sm,
59 std::shared_ptr<CapabilitiesInterface> ci,
60 std::shared_ptr<PlanningStrategy> planning_strategy,
61 rclcpp::Duration min_plan_duration,
62 double planning_period,
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()) {};
73
79 void run();
80
85 void twist_cb(geometry_msgs::msg::TwistStamped::UniquePtr msg);
86
90 void bumper_pose_cb();
91
96
97 protected:
101 void initial_state();
102
106 void planning_state();
107
112 void waiting_state();
113
118 void paused_state();
119
123 void shutdown_state();
124
129 void guidance_state_cb(carma_planning_msgs::msg::GuidanceState::UniquePtr msg);
130
131 private:
132
133 VehicleState vehicle_state_; // The current state of the vehicle for populating planning requests
134
135 std::shared_ptr<ArbitratorStateMachine> sm_;
136 carma_ros2_utils::PubPtr<carma_planning_msgs::msg::ManeuverPlan> final_plan_pub_;
137 carma_ros2_utils::SubPtr<carma_planning_msgs::msg::GuidanceState> guidance_state_sub_;
138 std::shared_ptr<carma_ros2_utils::CarmaLifecycleNode> nh_;
139 rclcpp::Duration min_plan_duration_;
140 rclcpp::Duration time_between_plans_;
142 std::shared_ptr<CapabilitiesInterface> capabilities_interface_;
143 std::shared_ptr<PlanningStrategy> planning_strategy_;
146
147 geometry_msgs::msg::TransformStamped tf_;
148 // TF listenser
149 tf2_ros::Buffer tf2_buffer_;
150 std::unique_ptr<tf2_ros::TransformListener> tf2_listener_;
151 // transform from front bumper to map
152 tf2::Stamped<tf2::Transform> bumper_transform_;
154 };
155}
156
157#endif
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
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.
Definition: arbitrator.hpp:57
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
std::shared_ptr< CapabilitiesInterface > capabilities_interface_
Definition: arbitrator.hpp:142
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
std::shared_ptr< const WorldModel > WorldModelConstPtr
Definition: WorldModel.hpp:452
Struct defining the vehicle state required for maneuver planning.