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.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#ifndef __ARBITRATOR_INCLUDE_ARBITRATOR_NODE_HPP__
17#define __ARBITRATOR_INCLUDE_ARBITRATOR_NODE_HPP__
18
19#include <iostream>
20#include <vector>
21
22#include <rclcpp/rclcpp.hpp>
23#include <memory>
24#include <map>
25#include <string>
28#include <rapidjson/document.h>
29
30#include "arbitrator.hpp"
31#include "arbitrator_config.hpp"
37#include "tree_planner.hpp"
38
39
40namespace arbitrator
41{
49 class ArbitratorNode : public carma_ros2_utils::CarmaLifecycleNode
50 {
51 public:
55 explicit ArbitratorNode(const rclcpp::NodeOptions& options);
56
58 // Overrides
60 carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &);
61 carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &);
62
63 private:
64 // helper function to parse plugin_priorities param from yaml as a json
65 std::map<std::string, double> plugin_priorities_map_from_json(const std::string& json_string);
66 carma_ros2_utils::SubPtr<geometry_msgs::msg::TwistStamped> twist_sub_;
67
69 // wm listener pointer and pointer to the actual wm object
70 std::shared_ptr<carma_wm::WMListener> wm_listener_;
72 std::shared_ptr<Arbitrator> arbitrator_;
73 rclcpp::TimerBase::SharedPtr bumper_pose_timer_;
74 rclcpp::TimerBase::SharedPtr arbitrator_run_;
75
76 };
77
78} // namespace abitrator
79
80#endif
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 &)
std::shared_ptr< const WorldModel > WorldModelConstPtr
Definition: WorldModel.hpp:452