38 #include <atlascar_base/ManagerStatus.h>
39 #include <atlascar_base/ManagerCommand.h>
41 #include <atlascar_base/GearboxStatus.h>
42 #include <atlascar_base/GearboxCommand.h>
44 #include <human_driver_monitor/HumanDriverMonitorStatus.h>
45 #include <odometer/OdometerStatus.h>
47 #include <atlascar_base/ThrottleStatus.h>
48 #include <atlascar_base/ThrottleCommand.h>
50 #include <atlascar_base/PlcStatus.h>
51 #include <atlascar_base/PlcCommand.h>
53 #include <topic_priority/topic_priority.h>
57 namespace atlascar_base
95 Manager(
const ros::NodeHandle& nh);
117 void setupMessaging();
165 void commandCallback(
const atlascar_base::ManagerCommandPtr& command);
172 CarState getCurrentState();
179 void plcStatusCallback(
const atlascar_base::PlcStatusPtr& status);
186 void driverStatusCallback(
const human_driver_monitor::HumanDriverMonitorStatusPtr& status);
193 void odometerStatusCallback(
const odometer::OdometerStatusPtr& status);
200 void gearboxStatusCallback(
const atlascar_base::GearboxStatusPtr& status);
207 void throttleStatusCallback(
const atlascar_base::ThrottleStatusPtr& status);
214 void toOutgoingMessages(
const atlascar_base::ManagerCommandPtr& command);
221 void stateManager(
const atlascar_base::ManagerCommandPtr& command);
228 void stoppedToMoving();
235 void movingToStopped();
bool verbose_
Verbose mode.
atlascar_base::GearboxCommand gearbox_command_
Gearbox command message.
CarState
Car state machine status.
odometer::OdometerStatus odometer_status_
Velocity status message.
ros::Publisher command_throttle_pub_
Throttle command publisher.
ros::Subscriber command_sub_
Ros command subscriber.
atlascar_base::PlcCommand plc_command_
Plc command message.
CarState current_state
Current state of state machine.
ros::Publisher command_plc_pub_
Plc command publisher.
atlascar_base::ManagerStatus status_
Status message.
ros::Publisher command_gearbox_pub_
Gearbox command publisher.
ros::Subscriber status_gearbox_sub_
Gearbox status subscriber.
atlascar_base::ThrottleStatus throttle_status_
Throttle status message.
atlascar_base::ThrottleCommand throttle_command_
Throttle command message.
TopicQueuePriority< atlascar_base::ManagerCommandPtr > command_queue_
Command queue holding class.
sequentialState
Car stages.
ros::Subscriber status_odometer_sub_
Velocity status subscriber.
ros::Subscriber status_driver_sub_
Driver status subscriber.
ros::Subscriber status_plc_sub_
Plc status subscriber.
human_driver_monitor::HumanDriverMonitorStatus driver_status_
Driver status message.
ros::Publisher status_pub_
Ros status publisher.
ros::NodeHandle nh_
Ros node handler.
sequentialState mts_state
Moving to stopped state.
atlascar_base::ManagerCommandPtr safety_command_
Safety command message pointer.
sequentialState stm_state
Stopped to moving state.
atlascar_base::ManagerCommandPtr command_
Command message pointer.
atlascar_base::PlcStatus plc_status_
Plc status message.
Global management and control class.
atlascar_base::GearboxStatus gearbox_status_
Gearbox status message.
ros::Subscriber status_throttle_sub_
Throttle status subscriber.