mirror of https://github.com/ArduPilot/ardupilot
AP_Frsky_Telem: Plane support
This commit is contained in:
parent
b2b6c88edf
commit
5125846ac0
|
@ -61,7 +61,36 @@ void AP_Frsky_Telem::init(const AP_SerialManager &serial_manager, const char *fi
|
|||
|
||||
/*
|
||||
* init - perform required initialisation
|
||||
* for Plane and Rover
|
||||
* for Plane
|
||||
*/
|
||||
void AP_Frsky_Telem::init(const AP_SerialManager &serial_manager, const char *firmware_str, const uint8_t mav_type, AP_Float *fs_batt_voltage, AP_Float *fs_batt_mah)
|
||||
{
|
||||
// check for protocol configured for a serial port - only the first serial port with one of these protocols will then run (cannot have FrSky on multiple serial ports)
|
||||
if ((_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_D, 0))) {
|
||||
_protocol = AP_SerialManager::SerialProtocol_FrSky_D; // FrSky D protocol (D-receivers)
|
||||
} else if ((_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_SPort, 0))) {
|
||||
_protocol = AP_SerialManager::SerialProtocol_FrSky_SPort; // FrSky SPort protocol (X-receivers)
|
||||
} else if ((_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_SPort_Passthrough, 0))) {
|
||||
_protocol = AP_SerialManager::SerialProtocol_FrSky_SPort_Passthrough; // FrSky SPort and SPort Passthrough (OpenTX) protocols (X-receivers)
|
||||
// add firmware and frame info to message queue
|
||||
queue_message(MAV_SEVERITY_INFO, firmware_str);
|
||||
// save main parameters locally
|
||||
_params.mav_type = mav_type; // frame type (see MAV_TYPE in Mavlink definition file common.h)
|
||||
_params.fs_batt_voltage = fs_batt_voltage; // failsafe battery voltage in volts
|
||||
_params.fs_batt_mah = fs_batt_mah; // failsafe reserve capacity in mAh
|
||||
*_ap.value = 0; // ap bit-field
|
||||
}
|
||||
|
||||
if (_port != NULL) {
|
||||
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Frsky_Telem::tick, void));
|
||||
// we don't want flow control for either protocol
|
||||
_port->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* init - perform required initialisation
|
||||
* for Rover
|
||||
*/
|
||||
void AP_Frsky_Telem::init(const AP_SerialManager &serial_manager)
|
||||
{
|
||||
|
|
|
@ -118,6 +118,7 @@ public:
|
|||
|
||||
// init - perform required initialisation
|
||||
void init(const AP_SerialManager &serial_manager, const char *firmware_str, const uint8_t mav_type, AP_Float *fs_batt_voltage, AP_Float *fs_batt_mah, uint32_t *ap_value);
|
||||
void init(const AP_SerialManager &serial_manager, const char *firmware_str, const uint8_t mav_type, AP_Float *fs_batt_voltage, AP_Float *fs_batt_mah);
|
||||
void init(const AP_SerialManager &serial_manager);
|
||||
|
||||
// add statustext message to FrSky lib queue.
|
||||
|
@ -126,6 +127,9 @@ public:
|
|||
// update flight control mode. The control mode is vehicle type specific
|
||||
void update_control_mode(uint8_t mode) { _ap.control_mode = mode; }
|
||||
|
||||
// update whether we're flying (used for Plane)
|
||||
void set_is_flying(bool is_flying) { *_ap.value == is_flying ? (*_ap.value | AP_ISFLYING_FLAG) : (*_ap.value & (~AP_ISFLYING_FLAG)); }
|
||||
|
||||
// update error mask of sensors and subsystems. The mask uses the
|
||||
// MAV_SYS_STATUS_* values from mavlink. If a bit is set then it
|
||||
// indicates that the sensor or subsystem is present but not
|
||||
|
|
Loading…
Reference in New Issue