1 #ifndef _LOWER_CONTROLLER_H_     2 #define _LOWER_CONTROLLER_H_    18     void sendPosition(uint16_t _time, std::vector<int16_t>& _data);
    19     void remapAeroToRos(std::vector<int16_t>& _ros, std::vector<int16_t>& _aero);
    20     void remapRosToAero(std::vector<int16_t>& _aero, std::vector<int16_t>& _ros);
    21     void runScript(uint8_t _number, uint16_t _script);
 std::vector< int > aero_index_
std::vector< std::string > wheel_name_
std::vector< std::pair< int, std::string > > aero_table_
LowerController(const std::string &_port)
void onServo(bool _value)
void runScript(uint8_t _number, uint16_t _script)
static const uint32_t BAUDRATE
void remapRosToAero(std::vector< int16_t > &_aero, std::vector< int16_t > &_ros)
float getBatteryVoltage()
void getRobotStatus(int8_t _number)
void sendPosition(uint16_t _time, std::vector< int16_t > &_data)
struct robot_hardware::LowerController::RobotStatus robot_status_
std::vector< int > wheel_aero_index_
std::string getFirmwareVersion()
std::vector< std::string > name_
std::vector< int16_t > raw_data_
void remapAeroToRos(std::vector< int16_t > &_ros, std::vector< int16_t > &_aero)
void sendVelocity(std::vector< int16_t > &_data)
std::vector< std::pair< int, std::string > > wheel_table_
aero::controller::AeroCommand * lower_
std::vector< std::string > upper_name_