PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Public Member Functions | |
BST (int bus) | |
virtual | ~BST () |
virtual int | init () |
virtual int | probe () |
virtual int | info () |
virtual int | ioctl (device::file_t *filp, int cmd, unsigned long arg) |
void | stop () |
Static Public Member Functions | |
static void | start_trampoline (void *arg) |
Private Member Functions | |
void | start () |
void | Run () override |
template<typename T > | |
void | send_packet (BSTPacket< T > &packet) |
template<typename T_SEND , typename T_RECV > | |
void | send_packet (BSTPacket< T_SEND > &packet_send, BSTPacket< T_RECV > &packet_recv) |
uint16_t | swap_uint16 (uint16_t val) |
Byte swap unsigned short. More... | |
int16_t | swap_int16 (int16_t val) |
Byte swap short. More... | |
uint32_t | swap_uint32 (uint32_t val) |
Byte swap unsigned int. More... | |
int32_t | swap_int32 (int32_t val) |
Byte swap int. More... | |
Static Private Member Functions | |
static uint8_t | crc8 (uint8_t *data, size_t len) |
Private Attributes | |
bool | _should_run = false |
unsigned | _interval = 100 |
uORB::Subscription | _gps_sub {ORB_ID(vehicle_gps_position)} |
uORB::Subscription | _attitude_sub {ORB_ID(vehicle_attitude)} |
uORB::Subscription | _battery_sub {ORB_ID(battery_status)} |
px4::bst::BST::BST | ( | int | bus | ) |
Definition at line 192 of file bst.cpp.
Referenced by bst_main().
|
virtual |
Definition at line 198 of file bst.cpp.
References _should_run.
|
staticprivate |
|
virtual |
Definition at line 240 of file bst.cpp.
References ToneAlarmInterface::init(), and OK.
Referenced by bst_main().
|
inlinevirtual |
|
virtual |
Definition at line 205 of file bst.cpp.
References px4::bst::BSTDeviceInfoRequest::cmd, crc8(), px4::bst::BSTDeviceInfoReply::dev_name, px4::bst::BSTDeviceInfoReply::dev_name_len, px4::bst::BSTDeviceInfoReply::fw_id, px4::bst::BSTDeviceInfoReply::hw_id, px4::bst::BSTPacket< T >::length, OK, px4::bst::BSTPacket< T >::payload, send_packet(), swap_uint16(), swap_uint32(), px4::bst::BSTPacket< T >::type, and warnx.
|
overrideprivate |
Definition at line 253 of file bst.cpp.
References _attitude_sub, _battery_sub, _gps_sub, _interval, _should_run, vehicle_gps_position_s::alt, px4::bst::BSTGPSPosition::alt, px4::bst::BSTBattery::capacity, vehicle_gps_position_s::cog_rad, uORB::Subscription::copy(), px4::bst::BSTBattery::current, battery_status_s::current_a, battery_status_s::discharged_mah, vehicle_gps_position_s::eph, vehicle_gps_position_s::fix_type, gps, px4::bst::BSTGPSPosition::gs, px4::bst::BSTGPSPosition::heading, vehicle_gps_position_s::lat, px4::bst::BSTGPSPosition::lat, vehicle_gps_position_s::lon, px4::bst::BSTGPSPosition::lon, M_PI_F, px4::bst::BSTPacket< T >::payload, matrix::Euler< Type >::phi(), px4::bst::BSTAttitude::pitch, matrix::Euler< Type >::psi(), vehicle_attitude_s::q, px4::bst::BSTAttitude::roll, vehicle_gps_position_s::satellites_used, px4::bst::BSTGPSPosition::sats, send_packet(), swap_int16(), swap_int32(), swap_uint16(), matrix::Euler< Type >::theta(), px4::bst::BSTPacket< T >::type, uORB::Subscription::updated(), vehicle_gps_position_s::vel_m_s, px4::bst::BSTBattery::voltage, battery_status_s::voltage_v, and px4::bst::BSTAttitude::yaw.
|
inlineprivate |
Definition at line 144 of file bst.cpp.
References px4::bst::BSTPacket< T >::crc, crc8(), px4::bst::BSTPacket< T >::length, and px4::bst::BSTPacket< T >::type.
Referenced by probe(), and Run().
|
inlineprivate |
Definition at line 153 of file bst.cpp.
References px4::bst::BSTPacket< T >::crc, crc8(), data, px4::bst::BSTPacket< T >::length, and px4::bst::BSTPacket< T >::type.
|
private |
|
static |
void px4::bst::BST::stop | ( | ) |
|
inlineprivate |
|
inlineprivate |
|
inlineprivate |
|
inlineprivate |
|
private |
|
private |
|
private |
|
private |
|
private |