37 #include <atlascar_base/ManagerCommand.h>
38 #include <atlascar_base/ManagerStatus.h>
43 namespace atlascar_base
53 command_msg.priority = 1;
54 command_msg.lifetime = std::numeric_limits<double>::infinity();
56 command_msg.velocity = 0;
58 command_msg.auto_ignition = 1;
59 command_msg.auto_brake = 1;
60 command_msg.auto_direction = 1;
61 command_msg.auto_clutch = 1;
62 command_msg.auto_throttle = 1;
64 command_msg.direct_control = 2;
79 void setupMessaging();
136 double map(
double value,
double min_value,
double max_value,
double min_required,
double max_required);
138 void saveData(
string report_name);
144 void positive_velocity(
int value);
151 void neutral_velocity(
int value);
158 void neutral_velocity_parking(
int value);
164 void negative_velocity(
int value);
171 void parallel_parking(
int value);
178 void reversing(
int value);
185 void statusCallback(
const atlascar_base::ManagerStatusPtr& status);
CarState
Car state machine status.
ros::Publisher command_pub
Ros command publisher.
sequentialState pparking
Moving to stopped state.
atlascar_base::ManagerStatus status_msg
Status message.
Gamepad gamepad
Gamepad communication class.
Maneuvers(const ros::NodeHandle &nh_)
ros::NodeHandle nh
Ros node handler.
sequentialState rreverse
Moving to stopped state.
Generic gamepad operation class.
ros::Subscriber status_sub
Ros status subscriber.
atlascar_base::ManagerStatus status_memory
Status message memory.
atlascar_base::ManagerCommand command_msg
Command message.
int maneuver
Parking status.
ros::Subscriber command_sub_
Ros command subscriber.