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.
guidance_state_machine.hpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2018-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#pragma once
18
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>
23
24#include <rclcpp/rclcpp.hpp>
25
26namespace guidance
27{
29 {
30 public:
31
32 enum Signal
33 {
36 ENGAGE = 2,
40 PARK = 6,
41 };
42
43 enum State
44 {
45 OFF = 0,
48 ACTIVE = 3,
52 };
53
58 GuidanceStateMachine(rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger);
59
63 void onVehicleStatus(autoware_msgs::msg::VehicleStatus::UniquePtr msg);
64
69
73 void onGuidanceShutdown();
74
78 void onSetGuidanceActive(bool msg);
79
83 void onRoboticStatus(carma_driver_msgs::msg::RobotEnabled::UniquePtr msg);
84
88 void onRouteEvent(carma_planning_msgs::msg::RouteEvent::UniquePtr msg);
89
94
98 uint8_t getCurrentState();
99
100 private:
101
105 void onGuidanceSignal(Signal signal);
106
107 // a local variable keeps the current state machine state
109
110 // Previous robotic active status
112
113 // make one service call in ACTIVE state to engage
115
116 // Current vehicle speed in m/s. Used to handle end of route state transition.
117 double current_velocity_ = 0.0;
118
119 // Logger interface
120 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_;
121
122 };
123
124} // guidance
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.
void onRouteEvent(carma_planning_msgs::msg::RouteEvent::UniquePtr msg)
Handle route event message.
void onGuidanceInitialized()
Updates Guidance State Machine with INITIALIZED signal.
bool shouldCallSetEnableRobotic()
Indicate if SetEnableRobotic needs to be called in ACTIVE 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.