#include <seed_r7_lower_controller.h>
|
enum | error_bit_t {
can2_connection = 0,
can2_calibration = 1,
can2_motor_status = 2,
can2_temperature = 3,
can2_response = 4,
can2_step_out = 5,
can2_protective_stopped = 6,
can2_power = 7,
can1_connection = 8,
can1_calibration = 9,
can1_motor_status = 10,
can1_temperature = 11,
can1_response = 12,
can1_step_out = 13,
can1_protective_stopped = 14,
can1_power = 15
} |
|
|
static const uint32_t | BAUDRATE = 1000000 |
|
Definition at line 11 of file seed_r7_lower_controller.h.
◆ error_bit_t
Enumerator |
---|
can2_connection | |
can2_calibration | |
can2_motor_status | |
can2_temperature | |
can2_response | |
can2_step_out | |
can2_protective_stopped | |
can2_power | |
can1_connection | |
can1_calibration | |
can1_motor_status | |
can1_temperature | |
can1_response | |
can1_step_out | |
can1_protective_stopped | |
can1_power | |
Definition at line 57 of file seed_r7_lower_controller.h.
◆ LowerController()
robot_hardware::LowerController::LowerController |
( |
const std::string & |
_port | ) |
|
◆ ~LowerController()
robot_hardware::LowerController::~LowerController |
( |
| ) |
|
◆ checkRobotStatus()
void robot_hardware::LowerController::checkRobotStatus |
( |
| ) |
|
◆ getBatteryVoltage()
float robot_hardware::LowerController::getBatteryVoltage |
( |
| ) |
|
◆ getFirmwareVersion()
std::string robot_hardware::LowerController::getFirmwareVersion |
( |
| ) |
|
◆ getPosition()
void robot_hardware::LowerController::getPosition |
( |
| ) |
|
◆ getRobotStatus()
void robot_hardware::LowerController::getRobotStatus |
( |
int8_t |
_number | ) |
|
◆ onServo()
void robot_hardware::LowerController::onServo |
( |
bool |
_value | ) |
|
◆ remapAeroToRos()
void robot_hardware::LowerController::remapAeroToRos |
( |
std::vector< int16_t > & |
_ros, |
|
|
std::vector< int16_t > & |
_aero |
|
) |
| |
◆ remapRosToAero()
void robot_hardware::LowerController::remapRosToAero |
( |
std::vector< int16_t > & |
_aero, |
|
|
std::vector< int16_t > & |
_ros |
|
) |
| |
◆ runScript()
void robot_hardware::LowerController::runScript |
( |
uint8_t |
_number, |
|
|
uint16_t |
_script |
|
) |
| |
◆ sendPosition()
void robot_hardware::LowerController::sendPosition |
( |
uint16_t |
_time, |
|
|
std::vector< int16_t > & |
_data |
|
) |
| |
◆ sendVelocity()
void robot_hardware::LowerController::sendVelocity |
( |
std::vector< int16_t > & |
_data | ) |
|
◆ aero_index_
std::vector<int> robot_hardware::LowerController::aero_index_ |
◆ aero_table_
std::vector<std::pair<int,std::string> > robot_hardware::LowerController::aero_table_ |
◆ BAUDRATE
const uint32_t robot_hardware::LowerController::BAUDRATE = 1000000 |
|
staticprotected |
◆ comm_err_
bool robot_hardware::LowerController::comm_err_ |
◆ is_open_
bool robot_hardware::LowerController::is_open_ |
◆ lower_
◆ name_
std::vector<std::string> robot_hardware::LowerController::name_ |
◆ raw_data_
std::vector<int16_t> robot_hardware::LowerController::raw_data_ |
◆ robot_status_
◆ upper_name_
std::vector<std::string> robot_hardware::LowerController::upper_name_ |
◆ wheel_aero_index_
std::vector<int> robot_hardware::LowerController::wheel_aero_index_ |
◆ wheel_name_
std::vector<std::string> robot_hardware::LowerController::wheel_name_ |
◆ wheel_table_
std::vector<std::pair<int,std::string> > robot_hardware::LowerController::wheel_table_ |
The documentation for this class was generated from the following files: