Classes | Public Member Functions | Public Attributes | Protected Types | Protected Attributes | Static Protected Attributes | List of all members
robot_hardware::LowerController Class Reference

#include <seed_r7_lower_controller.h>

Classes

struct  RobotStatus
 

Public Member Functions

void checkRobotStatus ()
 
float getBatteryVoltage ()
 
std::string getFirmwareVersion ()
 
void getPosition ()
 
void getRobotStatus (int8_t _number)
 
 LowerController (const std::string &_port)
 
void onServo (bool _value)
 
void remapAeroToRos (std::vector< int16_t > &_ros, std::vector< int16_t > &_aero)
 
void remapRosToAero (std::vector< int16_t > &_aero, std::vector< int16_t > &_ros)
 
void runScript (uint8_t _number, uint16_t _script)
 
void sendPosition (uint16_t _time, std::vector< int16_t > &_data)
 
void sendVelocity (std::vector< int16_t > &_data)
 
 ~LowerController ()
 

Public Attributes

std::vector< int > aero_index_
 
std::vector< std::pair< int, std::string > > aero_table_
 
bool comm_err_
 
bool is_open_
 
std::vector< std::string > name_
 
std::vector< int16_t > raw_data_
 
struct robot_hardware::LowerController::RobotStatus robot_status_
 
std::vector< std::string > upper_name_
 
std::vector< int > wheel_aero_index_
 
std::vector< std::string > wheel_name_
 
std::vector< std::pair< int, std::string > > wheel_table_
 

Protected Types

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
}
 

Protected Attributes

aero::controller::AeroCommandlower_
 

Static Protected Attributes

static const uint32_t BAUDRATE = 1000000
 

Detailed Description

Definition at line 11 of file seed_r7_lower_controller.h.

Member Enumeration Documentation

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.

Constructor & Destructor Documentation

robot_hardware::LowerController::LowerController ( const std::string &  _port)

Definition at line 4 of file seed_r7_lower_controller.cpp.

robot_hardware::LowerController::~LowerController ( )

Definition at line 44 of file seed_r7_lower_controller.cpp.

Member Function Documentation

void robot_hardware::LowerController::checkRobotStatus ( )

Definition at line 130 of file seed_r7_lower_controller.cpp.

float robot_hardware::LowerController::getBatteryVoltage ( )

Definition at line 111 of file seed_r7_lower_controller.cpp.

std::string robot_hardware::LowerController::getFirmwareVersion ( )

Definition at line 117 of file seed_r7_lower_controller.cpp.

void robot_hardware::LowerController::getPosition ( )

Definition at line 49 of file seed_r7_lower_controller.cpp.

void robot_hardware::LowerController::getRobotStatus ( int8_t  _number)

Definition at line 123 of file seed_r7_lower_controller.cpp.

void robot_hardware::LowerController::onServo ( bool  _value)

Definition at line 97 of file seed_r7_lower_controller.cpp.

void robot_hardware::LowerController::remapAeroToRos ( std::vector< int16_t > &  _ros,
std::vector< int16_t > &  _aero 
)

Definition at line 65 of file seed_r7_lower_controller.cpp.

void robot_hardware::LowerController::remapRosToAero ( std::vector< int16_t > &  _aero,
std::vector< int16_t > &  _ros 
)

Definition at line 74 of file seed_r7_lower_controller.cpp.

void robot_hardware::LowerController::runScript ( uint8_t  _number,
uint16_t  _script 
)

Definition at line 82 of file seed_r7_lower_controller.cpp.

void robot_hardware::LowerController::sendPosition ( uint16_t  _time,
std::vector< int16_t > &  _data 
)

Definition at line 56 of file seed_r7_lower_controller.cpp.

void robot_hardware::LowerController::sendVelocity ( std::vector< int16_t > &  _data)

Definition at line 86 of file seed_r7_lower_controller.cpp.

Member Data Documentation

std::vector<int> robot_hardware::LowerController::aero_index_

Definition at line 34 of file seed_r7_lower_controller.h.

std::vector<std::pair<int,std::string> > robot_hardware::LowerController::aero_table_

Definition at line 35 of file seed_r7_lower_controller.h.

const uint32_t robot_hardware::LowerController::BAUDRATE = 1000000
staticprotected

Definition at line 55 of file seed_r7_lower_controller.h.

bool robot_hardware::LowerController::comm_err_

Definition at line 41 of file seed_r7_lower_controller.h.

bool robot_hardware::LowerController::is_open_

Definition at line 29 of file seed_r7_lower_controller.h.

aero::controller::AeroCommand* robot_hardware::LowerController::lower_
protected

Definition at line 54 of file seed_r7_lower_controller.h.

std::vector<std::string> robot_hardware::LowerController::name_

Definition at line 33 of file seed_r7_lower_controller.h.

std::vector<int16_t> robot_hardware::LowerController::raw_data_

Definition at line 30 of file seed_r7_lower_controller.h.

struct robot_hardware::LowerController::RobotStatus robot_hardware::LowerController::robot_status_
std::vector<std::string> robot_hardware::LowerController::upper_name_

Definition at line 32 of file seed_r7_lower_controller.h.

std::vector<int> robot_hardware::LowerController::wheel_aero_index_

Definition at line 38 of file seed_r7_lower_controller.h.

std::vector<std::string> robot_hardware::LowerController::wheel_name_

Definition at line 37 of file seed_r7_lower_controller.h.

std::vector<std::pair<int,std::string> > robot_hardware::LowerController::wheel_table_

Definition at line 39 of file seed_r7_lower_controller.h.


The documentation for this class was generated from the following files:


seed_r7_ros_controller
Author(s): Yohei Kakiuchi
autogenerated on Sun Apr 18 2021 02:40:34