mirror of https://github.com/ArduPilot/ardupilot
AP_MSP: removed unnecessary pure virtual methods
This commit is contained in:
parent
e1b12fbee3
commit
53ea385291
|
@ -576,6 +576,44 @@ void AP_MSP_Telem_Backend::msp_handle_airspeed(const MSP::msp_airspeed_data_mess
|
|||
#endif
|
||||
}
|
||||
|
||||
MSPCommandResult AP_MSP_Telem_Backend::msp_process_out_api_version(sbuf_t *dst)
|
||||
{
|
||||
const struct {
|
||||
uint8_t proto;
|
||||
uint8_t major;
|
||||
uint8_t minor;
|
||||
} api_version {
|
||||
proto : MSP_PROTOCOL_VERSION,
|
||||
major : API_VERSION_MAJOR,
|
||||
minor : API_VERSION_MINOR
|
||||
};
|
||||
|
||||
sbuf_write_data(dst, &api_version, sizeof(api_version));
|
||||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
MSPCommandResult AP_MSP_Telem_Backend::msp_process_out_fc_version(sbuf_t *dst)
|
||||
{
|
||||
const struct {
|
||||
uint8_t major;
|
||||
uint8_t minor;
|
||||
uint8_t patch;
|
||||
} fc_version {
|
||||
major : FC_VERSION_MAJOR,
|
||||
minor : FC_VERSION_MINOR,
|
||||
patch : FC_VERSION_PATCH_LEVEL
|
||||
};
|
||||
|
||||
sbuf_write_data(dst, &fc_version, sizeof(fc_version));
|
||||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
MSPCommandResult AP_MSP_Telem_Backend::msp_process_out_fc_variant(sbuf_t *dst)
|
||||
{
|
||||
sbuf_write_data(dst, "ARDU", FLIGHT_CONTROLLER_IDENTIFIER_LENGTH);
|
||||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
MSPCommandResult AP_MSP_Telem_Backend::msp_process_out_raw_gps(sbuf_t *dst)
|
||||
{
|
||||
#if OSD_ENABLED
|
||||
|
|
|
@ -191,9 +191,9 @@ protected:
|
|||
virtual AP_SerialManager::SerialProtocol get_serial_protocol() const = 0;
|
||||
|
||||
// implementation specific MSP out command processing
|
||||
virtual MSP::MSPCommandResult msp_process_out_api_version(MSP::sbuf_t *dst) = 0;
|
||||
virtual MSP::MSPCommandResult msp_process_out_fc_version(MSP::sbuf_t *dst) = 0;
|
||||
virtual MSP::MSPCommandResult msp_process_out_fc_variant(MSP::sbuf_t *dst) = 0;
|
||||
virtual MSP::MSPCommandResult msp_process_out_api_version(MSP::sbuf_t *dst);
|
||||
virtual MSP::MSPCommandResult msp_process_out_fc_version(MSP::sbuf_t *dst);
|
||||
virtual MSP::MSPCommandResult msp_process_out_fc_variant(MSP::sbuf_t *dst);
|
||||
virtual MSP::MSPCommandResult msp_process_out_uid(MSP::sbuf_t *dst);
|
||||
virtual MSP::MSPCommandResult msp_process_out_board_info(MSP::sbuf_t *dst);
|
||||
virtual MSP::MSPCommandResult msp_process_out_build_info(MSP::sbuf_t *dst);
|
||||
|
|
|
@ -82,38 +82,6 @@ uint32_t AP_MSP_Telem_DJI::get_osd_flight_mode_bitmask(void)
|
|||
return mode_mask;
|
||||
}
|
||||
|
||||
MSPCommandResult AP_MSP_Telem_DJI::msp_process_out_api_version(sbuf_t *dst)
|
||||
{
|
||||
const struct {
|
||||
uint8_t proto;
|
||||
uint8_t major;
|
||||
uint8_t minor;
|
||||
} api_version {
|
||||
proto : MSP_PROTOCOL_VERSION,
|
||||
major : API_VERSION_MAJOR,
|
||||
minor : API_VERSION_MINOR
|
||||
};
|
||||
|
||||
sbuf_write_data(dst, &api_version, sizeof(api_version));
|
||||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
MSPCommandResult AP_MSP_Telem_DJI::msp_process_out_fc_version(sbuf_t *dst)
|
||||
{
|
||||
const struct {
|
||||
uint8_t major;
|
||||
uint8_t minor;
|
||||
uint8_t patch;
|
||||
} fc_version {
|
||||
major : FC_VERSION_MAJOR,
|
||||
minor : FC_VERSION_MINOR,
|
||||
patch : FC_VERSION_PATCH_LEVEL
|
||||
};
|
||||
|
||||
sbuf_write_data(dst, &fc_version, sizeof(fc_version));
|
||||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
MSPCommandResult AP_MSP_Telem_DJI::msp_process_out_fc_variant(sbuf_t *dst)
|
||||
{
|
||||
sbuf_write_data(dst, "BTFL", FLIGHT_CONTROLLER_IDENTIFIER_LENGTH);
|
||||
|
|
|
@ -55,8 +55,6 @@ public:
|
|||
AP_SerialManager::SerialProtocol get_serial_protocol() const override { return AP_SerialManager::SerialProtocol::SerialProtocol_DJI_FPV; };
|
||||
uint32_t get_osd_flight_mode_bitmask(void) override;
|
||||
void hide_osd_items(void) override;
|
||||
MSP::MSPCommandResult msp_process_out_api_version(MSP::sbuf_t *dst) override;
|
||||
MSP::MSPCommandResult msp_process_out_fc_version(MSP::sbuf_t *dst) override;
|
||||
MSP::MSPCommandResult msp_process_out_fc_variant(MSP::sbuf_t *dst) override;
|
||||
MSP::MSPCommandResult msp_process_out_esc_sensor_data(MSP::sbuf_t *dst) override;
|
||||
|
||||
|
|
|
@ -25,38 +25,6 @@ extern const AP_HAL::HAL& hal;
|
|||
|
||||
using namespace MSP;
|
||||
|
||||
MSPCommandResult AP_MSP_Telem_DisplayPort::msp_process_out_api_version(sbuf_t *dst)
|
||||
{
|
||||
const struct {
|
||||
uint8_t proto;
|
||||
uint8_t major;
|
||||
uint8_t minor;
|
||||
} api_version {
|
||||
proto : MSP_PROTOCOL_VERSION,
|
||||
major : API_VERSION_MAJOR,
|
||||
minor : API_VERSION_MINOR
|
||||
};
|
||||
|
||||
sbuf_write_data(dst, &api_version, sizeof(api_version));
|
||||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
MSPCommandResult AP_MSP_Telem_DisplayPort::msp_process_out_fc_version(sbuf_t *dst)
|
||||
{
|
||||
const struct {
|
||||
uint8_t major;
|
||||
uint8_t minor;
|
||||
uint8_t patch;
|
||||
} fc_version {
|
||||
major : FC_VERSION_MAJOR,
|
||||
minor : FC_VERSION_MINOR,
|
||||
patch : FC_VERSION_PATCH_LEVEL
|
||||
};
|
||||
|
||||
sbuf_write_data(dst, &fc_version, sizeof(fc_version));
|
||||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
MSPCommandResult AP_MSP_Telem_DisplayPort::msp_process_out_fc_variant(sbuf_t *dst)
|
||||
{
|
||||
const AP_MSP *msp = AP::msp();
|
||||
|
|
|
@ -28,8 +28,6 @@ public:
|
|||
bool use_msp_thread() const override { return false; }
|
||||
AP_SerialManager::SerialProtocol get_serial_protocol() const override { return AP_SerialManager::SerialProtocol::SerialProtocol_MSP_DisplayPort; };
|
||||
|
||||
MSP::MSPCommandResult msp_process_out_api_version(MSP::sbuf_t *dst) override;
|
||||
MSP::MSPCommandResult msp_process_out_fc_version(MSP::sbuf_t *dst) override;
|
||||
MSP::MSPCommandResult msp_process_out_fc_variant(MSP::sbuf_t *dst) override;
|
||||
};
|
||||
|
||||
|
|
|
@ -25,42 +25,4 @@ extern const AP_HAL::HAL& hal;
|
|||
|
||||
using namespace MSP;
|
||||
|
||||
MSPCommandResult AP_MSP_Telem_Generic::msp_process_out_api_version(sbuf_t *dst)
|
||||
{
|
||||
const struct {
|
||||
uint8_t proto;
|
||||
uint8_t major;
|
||||
uint8_t minor;
|
||||
} api_version {
|
||||
proto : MSP_PROTOCOL_VERSION,
|
||||
major : API_VERSION_MAJOR,
|
||||
minor : API_VERSION_MINOR
|
||||
};
|
||||
|
||||
sbuf_write_data(dst, &api_version, sizeof(api_version));
|
||||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
MSPCommandResult AP_MSP_Telem_Generic::msp_process_out_fc_version(sbuf_t *dst)
|
||||
{
|
||||
const struct {
|
||||
uint8_t major;
|
||||
uint8_t minor;
|
||||
uint8_t patch;
|
||||
} fc_version {
|
||||
major : FC_VERSION_MAJOR,
|
||||
minor : FC_VERSION_MINOR,
|
||||
patch : FC_VERSION_PATCH_LEVEL
|
||||
};
|
||||
|
||||
sbuf_write_data(dst, &fc_version, sizeof(fc_version));
|
||||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
MSPCommandResult AP_MSP_Telem_Generic::msp_process_out_fc_variant(sbuf_t *dst)
|
||||
{
|
||||
sbuf_write_data(dst, "ARDU", FLIGHT_CONTROLLER_IDENTIFIER_LENGTH);
|
||||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
#endif //HAL_MSP_ENABLED
|
||||
|
|
|
@ -26,9 +26,6 @@ class AP_MSP_Telem_Generic : public AP_MSP_Telem_Backend
|
|||
public:
|
||||
bool is_scheduler_enabled() const override { return false; }
|
||||
AP_SerialManager::SerialProtocol get_serial_protocol() const override { return AP_SerialManager::SerialProtocol::SerialProtocol_MSP; };
|
||||
MSP::MSPCommandResult msp_process_out_api_version(MSP::sbuf_t *dst) override;
|
||||
MSP::MSPCommandResult msp_process_out_fc_version(MSP::sbuf_t *dst) override;
|
||||
MSP::MSPCommandResult msp_process_out_fc_variant(MSP::sbuf_t *dst) override;
|
||||
};
|
||||
|
||||
#endif //HAL_MSP_ENABLED
|
||||
|
|
Loading…
Reference in New Issue