38 auto ci = std::make_shared<arbitrator::CapabilitiesInterface>(shared_from_this());
49 std::string json_string;
50 get_parameter<std::string>(
"plugin_priorities", json_string);
54 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"arbitrator"),
"Arbitrator Loaded Params: " <<
config_);
56 std::shared_ptr<arbitrator::CostFunction> cf;
61 cf = std::make_shared<arbitrator::FixedPriorityCostFunction>(fpcf);
63 cscf.
init(shared_from_this());
64 cf = std::make_shared<arbitrator::CostSystemCostFunction>(cscf);
69 auto png = std::make_shared<arbitrator::PluginNeighborGenerator<arbitrator::CapabilitiesInterface>>(ci);
73 this->get_node_base_interface(), this->get_node_logging_interface(),
74 this->get_node_topics_interface(), this->get_node_parameters_interface()
81 std::make_shared<ArbitratorStateMachine>(sm),
83 std::make_shared<TreePlanner>(tp),
93 return CallbackReturn::SUCCESS;
99 std::chrono::milliseconds(100),
104 [
this]() {this->arbitrator_->run();});
108 RCLCPP_INFO_STREAM(rclcpp::get_logger(
"arbitrator"),
"Arbitrator started, beginning arbitrator state machine.");
109 return CallbackReturn::SUCCESS;
114 std::map<std::string, double> map;
116 rapidjson::Document d;
117 if(d.Parse(json_string.c_str()).HasParseError())
119 RCLCPP_WARN(rclcpp::get_logger(
"arbitrator"),
"Failed to parse plugin_priorities map. Invalid json structure");
122 if (!d.HasMember(
"plugin_priorities")) {
123 RCLCPP_WARN(rclcpp::get_logger(
"arbitrator"),
"No plugin_priorities found in arbitrator config");
126 rapidjson::Value& map_value = d[
"plugin_priorities"];
128 for (rapidjson::Value::ConstMemberIterator it = map_value.MemberBegin();
129 it != map_value.MemberEnd(); it++)
131 map[it->name.GetString()] = it->value.GetDouble();
140#include "rclcpp_components/register_node_macro.hpp"
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.
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.
double planning_frequency
double target_plan_duration
std::map< std::string, double > plugin_priorities