19#include <carma_planning_msgs/msg/guidance_state.hpp>
20#include <carma_driver_msgs/msg/robot_enabled.hpp>
21#include <carma_planning_msgs/msg/route_event.hpp>
22#include <autoware_msgs/msg/vehicle_status.hpp>
24#include <rclcpp/rclcpp.hpp>
83 void onRoboticStatus(carma_driver_msgs::msg::RobotEnabled::UniquePtr msg);
88 void onRouteEvent(carma_planning_msgs::msg::RouteEvent::UniquePtr msg);
120 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
logger_;
void onGuidanceShutdown()
Updates Guidance State Machine with SHUTDOWN signal.
void onRoboticStatus(carma_driver_msgs::msg::RobotEnabled::UniquePtr msg)
Handle robotic_status message from ROS network.
uint8_t getCurrentState()
Get current state machine status.
void onVehicleStatus(autoware_msgs::msg::VehicleStatus::UniquePtr msg)
Handle vehicle status message from ROS network.
bool robotic_active_status_
void onRouteEvent(carma_planning_msgs::msg::RouteEvent::UniquePtr msg)
Handle route event message.
bool called_robotic_engage_in_active_
void onGuidanceInitialized()
Updates Guidance State Machine with INITIALIZED signal.
bool shouldCallSetEnableRobotic()
Indicate if SetEnableRobotic needs to be called in ACTIVE state.
State current_guidance_state_
void onGuidanceSignal(Signal signal)
Actual state machine logic driven by signal enum.
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_
GuidanceStateMachine(rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger)
constructor for GuidanceStateMachine
void onSetGuidanceActive(bool msg)
Handle set_guidance_active service call from ROS network.