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_node.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_node.hpp"
18
19
20namespace arbitrator
21{
22 ArbitratorNode::ArbitratorNode(const rclcpp::NodeOptions& options) : carma_ros2_utils::CarmaLifecycleNode(options)
23 {
24 // Create initial config
25 config_ = Config();
26
27 config_.min_plan_duration = declare_parameter<double>("min_plan_duration", config_.min_plan_duration);
28 config_.target_plan_duration = declare_parameter<double>("target_plan_duration", config_.target_plan_duration);
29 config_.planning_frequency = declare_parameter<double>("planning_frequency", config_.planning_frequency);
30 config_.beam_width = declare_parameter<int>("beam_width", config_.beam_width);
31 config_.use_fixed_costs = declare_parameter<bool>("use_fixed_costs", config_.use_fixed_costs);
32 config_.plugin_priorities = plugin_priorities_map_from_json(declare_parameter<std::string>("plugin_priorities", ""));
33 }
34
35 carma_ros2_utils::CallbackReturn ArbitratorNode::handle_on_configure(const rclcpp_lifecycle::State &)
36 {
37 // Handle dependency injection
38 auto ci = std::make_shared<arbitrator::CapabilitiesInterface>(shared_from_this());
40
41 // Reset config
42 config_ = Config();
43
44 get_parameter<double>("min_plan_duration", config_.min_plan_duration);
45 get_parameter<double>("target_plan_duration", config_.target_plan_duration);
46 get_parameter<double>("planning_frequency", config_.planning_frequency);
47 get_parameter<int>("beam_width", config_.beam_width);
48 get_parameter<bool>("use_fixed_costs", config_.use_fixed_costs);
49 std::string json_string;
50 get_parameter<std::string>("plugin_priorities", json_string);
51
53
54 RCLCPP_INFO_STREAM(rclcpp::get_logger("arbitrator"), "Arbitrator Loaded Params: " << config_);
55
56 std::shared_ptr<arbitrator::CostFunction> cf;
58
61 cf = std::make_shared<arbitrator::FixedPriorityCostFunction>(fpcf);
62 } else {
63 cscf.init(shared_from_this());
64 cf = std::make_shared<arbitrator::CostSystemCostFunction>(cscf);
65 }
66
67 auto bss = std::make_shared<arbitrator::BeamSearchStrategy>(config_.beam_width);
68
69 auto png = std::make_shared<arbitrator::PluginNeighborGenerator<arbitrator::CapabilitiesInterface>>(ci);
70 arbitrator::TreePlanner tp(cf, png, bss, rclcpp::Duration(config_.target_plan_duration* 1e9));
71
72 wm_listener_ = std::make_shared<carma_wm::WMListener>(
73 this->get_node_base_interface(), this->get_node_logging_interface(),
74 this->get_node_topics_interface(), this->get_node_parameters_interface()
75 );
76
77 wm_ = wm_listener_->getWorldModel();
78
79 arbitrator_ = std::make_shared<Arbitrator>(
80 shared_from_this(),
81 std::make_shared<ArbitratorStateMachine>(sm),
82 ci,
83 std::make_shared<TreePlanner>(tp),
84 rclcpp::Duration(config_.min_plan_duration* 1e9),
86 wm_ );
87
88
89 twist_sub_ = create_subscription<geometry_msgs::msg::TwistStamped>("current_velocity", 1, std::bind(&Arbitrator::twist_cb, arbitrator_.get(), std::placeholders::_1));
90
91 arbitrator_->initializeBumperTransformLookup();
92
93 return CallbackReturn::SUCCESS;
94 }
95
96 carma_ros2_utils::CallbackReturn ArbitratorNode::handle_on_activate(const rclcpp_lifecycle::State &)
97 {
98 bumper_pose_timer_ = create_timer(get_clock(),
99 std::chrono::milliseconds(100),
100 [this]() {this->arbitrator_->bumper_pose_cb();});
101
102 arbitrator_run_ = create_timer(get_clock(),
103 std::chrono::duration<double>(1/(config_.planning_frequency * 2 )), //there is waiting state between each planning state
104 [this]() {this->arbitrator_->run();});
105 //The intention is to keep the arbitrator planning at intended frequency - 1s. Looks like ROS2 conversion kept the WAITING state from ROS1,
106 //which occurs between PLANNING state in the state machine. So if the timer calls state callback each 1 second, the arbitrator ends up planning
107 //every 2s due to PLANNING > WAITING > PLANNING transition. That's why the frequency is doubled.
108 RCLCPP_INFO_STREAM(rclcpp::get_logger("arbitrator"), "Arbitrator started, beginning arbitrator state machine.");
109 return CallbackReturn::SUCCESS;
110 }
111
112 std::map<std::string, double> ArbitratorNode::plugin_priorities_map_from_json(const std::string& json_string)
113 {
114 std::map<std::string, double> map;
115
116 rapidjson::Document d;
117 if(d.Parse(json_string.c_str()).HasParseError())
118 {
119 RCLCPP_WARN(rclcpp::get_logger("arbitrator"), "Failed to parse plugin_priorities map. Invalid json structure");
120 return map;
121 }
122 if (!d.HasMember("plugin_priorities")) {
123 RCLCPP_WARN(rclcpp::get_logger("arbitrator"), "No plugin_priorities found in arbitrator config");
124 return map;
125 }
126 rapidjson::Value& map_value = d["plugin_priorities"];
127
128 for (rapidjson::Value::ConstMemberIterator it = map_value.MemberBegin();
129 it != map_value.MemberEnd(); it++)
130 {
131 map[it->name.GetString()] = it->value.GetDouble();
132 }
133 return map;
134
135 }
136
137}
138
139
140#include "rclcpp_components/register_node_macro.hpp"
141
142// Register the component with class_loader
143RCLCPP_COMPONENTS_REGISTER_NODE(arbitrator::ArbitratorNode)
std::map< std::string, double > plugin_priorities_map_from_json(const std::string &json_string)
rclcpp::TimerBase::SharedPtr bumper_pose_timer_
carma_wm::WorldModelConstPtr wm_
rclcpp::TimerBase::SharedPtr arbitrator_run_
carma_ros2_utils::SubPtr< geometry_msgs::msg::TwistStamped > twist_sub_
ArbitratorNode(const rclcpp::NodeOptions &options)
Constructor.
std::shared_ptr< Arbitrator > arbitrator_
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)
std::shared_ptr< carma_wm::WMListener > wm_listener_
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &)
void twist_cb(geometry_msgs::msg::TwistStamped::UniquePtr msg)
Callback for the twist subscriber, which will store latest twist locally.
Definition: arbitrator.cpp:206
Implementation of the CostFunction interface.
void init(std::shared_ptr< carma_ros2_utils::CarmaLifecycleNode > nh)
Implementation of the CostFunction interface.
Implementation of PlanningStrategy using a generic tree search algorithm.
std::map< std::string, double > plugin_priorities