20#include <rclcpp/rclcpp.hpp>
21#include <carma_ros2_utils/carma_lifecycle_node.hpp>
26#include <carma_msgs/msg/light_bar_cda_type.hpp>
27#include <carma_msgs/msg/light_bar_indicator.hpp>
28#include <carma_msgs/msg/light_bar_indicator_controllers.hpp>
29#include <carma_driver_msgs/msg/light_bar_status.hpp>
30#include <carma_planning_msgs/msg/guidance_state.hpp>
31#include <automotive_platform_msgs/msg/turn_signal_command.hpp>
33#include <carma_msgs/srv/request_indicator_control.hpp>
34#include <carma_msgs/srv/release_indicator_control.hpp>
35#include <carma_driver_msgs/srv/set_light_bar_indicator.hpp>
36#include <carma_driver_msgs/srv/set_lights.hpp>
57 output <<
"LightBarManager::Config { " << std::endl
58 <<
"spin_rate_hz: " <<
c.spin_rate_hz << std::endl
59 <<
"lightbar_priorities.size(): " <<
c.lightbar_priorities.size() << std::endl
60 <<
"lightbar_cda_table.size(): " <<
c.lightbar_cda_table.size() << std::endl
61 <<
"lightbar_ind_table.size(): " <<
c.lightbar_ind_table.size() << std::endl
83 std::shared_ptr<LightBarManagerWorker>
getWorker();
101 void turnSignalCallback(automotive_platform_msgs::msg::TurnSignalCommand::UniquePtr msg_ptr);
117 void processTurnSignal(
const automotive_platform_msgs::msg::TurnSignalCommand& msg);
129 const std::shared_ptr<carma_msgs::srv::RequestIndicatorControl::Request> req,
130 std::shared_ptr<carma_msgs::srv::RequestIndicatorControl::Response> resp);
132 const std::shared_ptr<carma_msgs::srv::ReleaseIndicatorControl::Request> req,
133 std::shared_ptr<carma_msgs::srv::ReleaseIndicatorControl::Response> resp);
135 const std::shared_ptr<carma_driver_msgs::srv::SetLightBarIndicator::Request> req,
136 std::shared_ptr<carma_driver_msgs::srv::SetLightBarIndicator::Response> resp);
153 std::shared_ptr<LightBarManagerWorker>
lbm_;
164#include "rclcpp_components/register_node_macro.hpp"
void turnOffAll()
Miscellaneous function that forces the state to disengaged and turn off all indicators....
carma_ros2_utils::PubPtr< carma_msgs::msg::LightBarIndicatorControllers > indicator_control_publisher_
void turnSignalCallback(automotive_platform_msgs::msg::TurnSignalCommand::UniquePtr msg_ptr)
Callback function for turning signal.
carma_ros2_utils::SubPtr< automotive_platform_msgs::msg::TurnSignalCommand > turn_signal_subscriber_
carma_ros2_utils::ClientPtr< carma_driver_msgs::srv::SetLights > lightbar_driver_client_
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)
bool requestControlCallBack(const std::shared_ptr< rmw_request_id_t >, const std::shared_ptr< carma_msgs::srv::RequestIndicatorControl::Request > req, std::shared_ptr< carma_msgs::srv::RequestIndicatorControl::Response > resp)
std::shared_ptr< LightBarManagerWorker > getWorker()
Get ptr to lightbar_manager_worker (for ease of unit testing)
carma_ros2_utils::ServicePtr< carma_msgs::srv::ReleaseIndicatorControl > release_control_server_
void processTurnSignal(const automotive_platform_msgs::msg::TurnSignalCommand &msg)
Turn signal callback function helper.
bool releaseControlCallBack(const std::shared_ptr< rmw_request_id_t >, const std::shared_ptr< carma_msgs::srv::ReleaseIndicatorControl::Request > req, std::shared_ptr< carma_msgs::srv::ReleaseIndicatorControl::Response > resp)
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &)
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::GuidanceState > guidance_state_subscriber_
int setIndicator(LightBarIndicator ind, IndicatorStatus ind_status, const std::string &requester_name)
Try to turn the given indicator ON or OFF (comm with hardware) upon the given component's request.
std::map< lightbar_manager::LightBarIndicator, std::string > prev_owners_before_turn_
FRIEND_TEST(LightBarManagerNodeTest, testTurnOffAll)
FRIEND_TEST(LightBarManagerNodeTest, testTurnSignalCallback)
std::shared_ptr< LightBarManagerWorker > lbm_
FRIEND_TEST(LightBarManagerNodeTest, testSetIndicator)
void stateChangeCallBack(carma_planning_msgs::msg::GuidanceState::UniquePtr msg_ptr)
LightBarManager(const rclcpp::NodeOptions &)
carma_ros2_utils::ServicePtr< carma_driver_msgs::srv::SetLightBarIndicator > set_indicator_server_
carma_ros2_utils::ServicePtr< carma_msgs::srv::RequestIndicatorControl > request_control_server_
rclcpp::TimerBase::SharedPtr pub_timer_
bool setIndicatorCallBack(const std::shared_ptr< rmw_request_id_t >, const std::shared_ptr< carma_driver_msgs::srv::SetLightBarIndicator::Request > req, std::shared_ptr< carma_driver_msgs::srv::SetLightBarIndicator::Response > resp)
std::vector< std::string > lightbar_priorities
std::vector< std::string > lightbar_cda_table
std::vector< std::string > lightbar_ind_table
friend std::ostream & operator<<(std::ostream &output, const Config &c)