mirror of https://github.com/ArduPilot/ardupilot
AP_MSP: cleanup namespace handling
using "using namespace MSP" in headers is a bad idea as it spreads to lots of cpp via includes. It is fine in a cpp file
This commit is contained in:
parent
3517ab9c45
commit
d8ed210b98
|
@ -28,6 +28,8 @@
|
|||
const uint16_t OSD_FLIGHT_MODE_FOCUS_TIME = 2000;
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace MSP;
|
||||
|
||||
const AP_Param::GroupInfo AP_MSP::var_info[] = {
|
||||
|
||||
// @Param: _OSD_NCELLS
|
||||
|
|
|
@ -31,8 +31,6 @@
|
|||
#define MSP_OSD_STEP_Y 32
|
||||
#define MSP_OSD_POS(osd_setting) (MSP_OSD_START + osd_setting->xpos*MSP_OSD_STEP_X + osd_setting->ypos*MSP_OSD_STEP_Y)
|
||||
|
||||
using namespace MSP;
|
||||
|
||||
class AP_MSP
|
||||
{
|
||||
friend class AP_MSP_Telem_Generic;
|
||||
|
@ -71,8 +69,8 @@ private:
|
|||
AP_Int8 _cellcount;
|
||||
|
||||
// these are the osd items we support for MSP OSD
|
||||
AP_OSD_Setting* _osd_item_settings[OSD_ITEM_COUNT];
|
||||
osd_config_t _osd_config;
|
||||
AP_OSD_Setting* _osd_item_settings[MSP::OSD_ITEM_COUNT];
|
||||
MSP::osd_config_t _osd_config;
|
||||
|
||||
struct {
|
||||
bool flashing_on; // OSD item flashing support
|
||||
|
@ -96,4 +94,4 @@ namespace AP
|
|||
AP_MSP *msp();
|
||||
};
|
||||
|
||||
#endif //HAL_MSP_ENABLED
|
||||
#endif //HAL_MSP_ENABLED
|
||||
|
|
|
@ -38,6 +38,8 @@
|
|||
extern const AP_HAL::HAL& hal;
|
||||
constexpr uint8_t AP_MSP_Telem_Backend::arrows[8];
|
||||
|
||||
using namespace MSP;
|
||||
|
||||
AP_MSP_Telem_Backend::AP_MSP_Telem_Backend(AP_HAL::UARTDriver *uart) : AP_RCTelemetry(MSP_TIME_SLOT_MAX)
|
||||
{
|
||||
_msp_port.uart = uart;
|
||||
|
@ -464,12 +466,12 @@ MSPCommandResult AP_MSP_Telem_Backend::msp_process_sensor_command(uint16_t cmd_m
|
|||
|
||||
switch (cmd_msp) {
|
||||
case MSP2_SENSOR_RANGEFINDER: {
|
||||
const msp_rangefinder_sensor_t pkt = *(const msp_rangefinder_sensor_t *)src->ptr;
|
||||
const MSP::msp_rangefinder_sensor_t pkt = *(const MSP::msp_rangefinder_sensor_t *)src->ptr;
|
||||
msp_handle_rangefinder(pkt);
|
||||
}
|
||||
break;
|
||||
case MSP2_SENSOR_OPTIC_FLOW: {
|
||||
const msp_opflow_sensor_t pkt = *(const msp_opflow_sensor_t *)src->ptr;
|
||||
const MSP::msp_opflow_sensor_t pkt = *(const MSP::msp_opflow_sensor_t *)src->ptr;
|
||||
msp_handle_opflow(pkt);
|
||||
}
|
||||
break;
|
||||
|
@ -478,7 +480,7 @@ MSPCommandResult AP_MSP_Telem_Backend::msp_process_sensor_command(uint16_t cmd_m
|
|||
return MSP_RESULT_NO_REPLY;
|
||||
}
|
||||
|
||||
void AP_MSP_Telem_Backend::msp_handle_opflow(const msp_opflow_sensor_t &pkt)
|
||||
void AP_MSP_Telem_Backend::msp_handle_opflow(const MSP::msp_opflow_sensor_t &pkt)
|
||||
{
|
||||
OpticalFlow *optflow = AP::opticalflow();
|
||||
if (optflow == nullptr) {
|
||||
|
@ -487,7 +489,7 @@ void AP_MSP_Telem_Backend::msp_handle_opflow(const msp_opflow_sensor_t &pkt)
|
|||
optflow->handle_msp(pkt);
|
||||
}
|
||||
|
||||
void AP_MSP_Telem_Backend::msp_handle_rangefinder(const msp_rangefinder_sensor_t &pkt)
|
||||
void AP_MSP_Telem_Backend::msp_handle_rangefinder(const MSP::msp_rangefinder_sensor_t &pkt)
|
||||
{
|
||||
#if HAL_MSP_RANGEFINDER_ENABLED
|
||||
RangeFinder *rangefinder = AP::rangefinder();
|
||||
|
|
|
@ -29,8 +29,6 @@
|
|||
#define MSP_TXT_BUFFER_SIZE 15U // 11 + 3 utf8 chars + terminator
|
||||
#define MSP_TXT_VISIBLE_CHARS 11U
|
||||
|
||||
using namespace MSP;
|
||||
|
||||
class AP_MSP;
|
||||
|
||||
class AP_MSP_Telem_Backend : AP_RCTelemetry
|
||||
|
@ -44,7 +42,7 @@ public:
|
|||
float batt_voltage_v;
|
||||
int32_t batt_capacity_mah;
|
||||
uint8_t batt_cellcount;
|
||||
battery_state_e batt_state;
|
||||
MSP::battery_state_e batt_state;
|
||||
} battery_state_t;
|
||||
|
||||
typedef struct PACKED gps_state_s {
|
||||
|
@ -133,17 +131,17 @@ protected:
|
|||
uint64_t osd_hidden_items_bitmask;
|
||||
|
||||
// MSP decoder status
|
||||
msp_port_t _msp_port;
|
||||
MSP::msp_port_t _msp_port;
|
||||
|
||||
// passthrough WFQ scheduler
|
||||
bool is_packet_ready(uint8_t idx, bool queue_empty) override;
|
||||
void process_packet(uint8_t idx) override;
|
||||
void adjust_packet_weight(bool queue_empty) override {};
|
||||
void adjust_packet_weight(bool queue_empty) override {}
|
||||
void setup_wfq_scheduler(void) override;
|
||||
bool get_next_msg_chunk(void) override
|
||||
{
|
||||
return true;
|
||||
};
|
||||
}
|
||||
|
||||
// telemetry helpers
|
||||
uint8_t calc_cell_count(float battery_voltage);
|
||||
|
@ -156,40 +154,42 @@ protected:
|
|||
|
||||
// MSP parsing
|
||||
void msp_process_received_command();
|
||||
MSPCommandResult msp_process_command(msp_packet_t *cmd, msp_packet_t *reply);
|
||||
MSPCommandResult msp_process_sensor_command(uint16_t cmd_msp, sbuf_t *src);
|
||||
MSPCommandResult msp_process_out_command(uint16_t cmd_msp, sbuf_t *dst);
|
||||
MSP::MSPCommandResult msp_process_command(MSP::msp_packet_t *cmd, MSP::msp_packet_t *reply);
|
||||
MSP::MSPCommandResult msp_process_sensor_command(uint16_t cmd_msp, MSP::sbuf_t *src);
|
||||
MSP::MSPCommandResult msp_process_out_command(uint16_t cmd_msp, MSP::sbuf_t *dst);
|
||||
|
||||
// MSP sensor command processing
|
||||
void msp_handle_opflow(const msp_opflow_sensor_t &pkt);
|
||||
void msp_handle_rangefinder(const msp_rangefinder_sensor_t &pkt);
|
||||
void msp_handle_opflow(const MSP::msp_opflow_sensor_t &pkt);
|
||||
void msp_handle_rangefinder(const MSP::msp_rangefinder_sensor_t &pkt);
|
||||
|
||||
// implementation specific helpers
|
||||
// custom masks are needed for vendor specific settings
|
||||
virtual uint32_t get_osd_flight_mode_bitmask(void)
|
||||
{
|
||||
return 0;
|
||||
}; // custom masks are needed for vendor specific settings
|
||||
}
|
||||
|
||||
virtual bool is_scheduler_enabled() = 0; // only osd backends should allow a push type telemetry
|
||||
|
||||
// implementation specific MSP out command processing
|
||||
virtual MSPCommandResult msp_process_out_api_version(sbuf_t *dst) = 0;
|
||||
virtual MSPCommandResult msp_process_out_fc_version(sbuf_t *dst) = 0;
|
||||
virtual MSPCommandResult msp_process_out_fc_variant(sbuf_t *dst) = 0;
|
||||
virtual MSPCommandResult msp_process_out_uid(sbuf_t *dst);
|
||||
virtual MSPCommandResult msp_process_out_board_info(sbuf_t *dst);
|
||||
virtual MSPCommandResult msp_process_out_build_info(sbuf_t *dst);
|
||||
virtual MSPCommandResult msp_process_out_name(sbuf_t *dst);
|
||||
virtual MSPCommandResult msp_process_out_status(sbuf_t *dst);
|
||||
virtual MSPCommandResult msp_process_out_osd_config(sbuf_t *dst);
|
||||
virtual MSPCommandResult msp_process_out_raw_gps(sbuf_t *dst);
|
||||
virtual MSPCommandResult msp_process_out_comp_gps(sbuf_t *dst);
|
||||
virtual MSPCommandResult msp_process_out_attitude(sbuf_t *dst);
|
||||
virtual MSPCommandResult msp_process_out_altitude(sbuf_t *dst);
|
||||
virtual MSPCommandResult msp_process_out_analog(sbuf_t *dst);
|
||||
virtual MSPCommandResult msp_process_out_battery_state(sbuf_t *dst);
|
||||
virtual MSPCommandResult msp_process_out_esc_sensor_data(sbuf_t *dst);
|
||||
virtual MSPCommandResult msp_process_out_rtc(sbuf_t *dst);
|
||||
virtual MSPCommandResult msp_process_out_rc(sbuf_t *dst);
|
||||
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_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);
|
||||
virtual MSP::MSPCommandResult msp_process_out_name(MSP::sbuf_t *dst);
|
||||
virtual MSP::MSPCommandResult msp_process_out_status(MSP::sbuf_t *dst);
|
||||
virtual MSP::MSPCommandResult msp_process_out_osd_config(MSP::sbuf_t *dst);
|
||||
virtual MSP::MSPCommandResult msp_process_out_raw_gps(MSP::sbuf_t *dst);
|
||||
virtual MSP::MSPCommandResult msp_process_out_comp_gps(MSP::sbuf_t *dst);
|
||||
virtual MSP::MSPCommandResult msp_process_out_attitude(MSP::sbuf_t *dst);
|
||||
virtual MSP::MSPCommandResult msp_process_out_altitude(MSP::sbuf_t *dst);
|
||||
virtual MSP::MSPCommandResult msp_process_out_analog(MSP::sbuf_t *dst);
|
||||
virtual MSP::MSPCommandResult msp_process_out_battery_state(MSP::sbuf_t *dst);
|
||||
virtual MSP::MSPCommandResult msp_process_out_esc_sensor_data(MSP::sbuf_t *dst);
|
||||
virtual MSP::MSPCommandResult msp_process_out_rtc(MSP::sbuf_t *dst);
|
||||
virtual MSP::MSPCommandResult msp_process_out_rc(MSP::sbuf_t *dst);
|
||||
};
|
||||
|
||||
#endif //HAL_MSP_ENABLED
|
||||
|
|
|
@ -22,6 +22,8 @@
|
|||
#if HAL_MSP_ENABLED
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace MSP;
|
||||
|
||||
bool AP_MSP_Telem_DJI::init_uart()
|
||||
{
|
||||
if (_msp_port.uart != nullptr) {
|
||||
|
@ -102,4 +104,4 @@ MSPCommandResult AP_MSP_Telem_DJI::msp_process_out_fc_variant(sbuf_t *dst)
|
|||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
#endif //HAL_MSP_ENABLED
|
||||
#endif //HAL_MSP_ENABLED
|
||||
|
|
|
@ -54,9 +54,9 @@ public:
|
|||
bool is_scheduler_enabled() override;
|
||||
uint32_t get_osd_flight_mode_bitmask(void) override;
|
||||
void hide_osd_items(void) override;
|
||||
MSPCommandResult msp_process_out_api_version(sbuf_t *dst) override;
|
||||
MSPCommandResult msp_process_out_fc_version(sbuf_t *dst) override;
|
||||
MSPCommandResult msp_process_out_fc_variant(sbuf_t *dst) 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;
|
||||
|
||||
enum : uint8_t {
|
||||
DJI_FLAG_ARM = 0,
|
||||
|
@ -68,4 +68,4 @@ public:
|
|||
};
|
||||
};
|
||||
|
||||
#endif //HAL_MSP_ENABLED
|
||||
#endif //HAL_MSP_ENABLED
|
||||
|
|
|
@ -23,6 +23,8 @@
|
|||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace MSP;
|
||||
|
||||
MSPCommandResult AP_MSP_Telem_Generic::msp_process_out_api_version(sbuf_t *dst)
|
||||
{
|
||||
sbuf_write_u8(dst, MSP_PROTOCOL_VERSION);
|
||||
|
@ -45,4 +47,4 @@ MSPCommandResult AP_MSP_Telem_Generic::msp_process_out_fc_variant(sbuf_t *dst)
|
|||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
#endif //HAL_MSP_ENABLED
|
||||
#endif //HAL_MSP_ENABLED
|
||||
|
|
|
@ -27,10 +27,10 @@ public:
|
|||
bool is_scheduler_enabled() override
|
||||
{
|
||||
return false;
|
||||
};
|
||||
MSPCommandResult msp_process_out_api_version(sbuf_t *dst) override;
|
||||
MSPCommandResult msp_process_out_fc_version(sbuf_t *dst) override;
|
||||
MSPCommandResult msp_process_out_fc_variant(sbuf_t *dst) 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;
|
||||
};
|
||||
|
||||
#endif //HAL_MSP_ENABLED
|
||||
#endif //HAL_MSP_ENABLED
|
||||
|
|
Loading…
Reference in New Issue