mirror of https://github.com/ArduPilot/ardupilot
Copter: create GCS subclass, use inheritted methods
This commit is contained in:
parent
b81e5a8562
commit
d9b45cc202
|
@ -99,6 +99,7 @@
|
|||
#include "config.h"
|
||||
|
||||
#include "GCS_Mavlink.h"
|
||||
#include "GCS_Copter.h"
|
||||
#include "AP_Rally.h" // Rally point library
|
||||
#include "AP_Arming.h"
|
||||
|
||||
|
@ -136,6 +137,7 @@
|
|||
class Copter : public AP_HAL::HAL::Callbacks {
|
||||
public:
|
||||
friend class GCS_MAVLINK_Copter;
|
||||
friend class GCS_Copter;
|
||||
friend class AP_Rally_Copter;
|
||||
friend class Parameters;
|
||||
friend class ParametersG2;
|
||||
|
@ -245,11 +247,8 @@ private:
|
|||
|
||||
// GCS selection
|
||||
AP_SerialManager serial_manager;
|
||||
static const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS;
|
||||
|
||||
GCS_MAVLINK_Copter gcs_chan[MAVLINK_COMM_NUM_BUFFERS];
|
||||
GCS _gcs; // avoid using this; use gcs()
|
||||
GCS &gcs() { return _gcs; }
|
||||
GCS_Copter _gcs; // avoid using this; use gcs()
|
||||
GCS_Copter &gcs() { return _gcs; }
|
||||
|
||||
// User variables
|
||||
#ifdef USERHOOK_VARIABLES
|
||||
|
|
|
@ -0,0 +1,15 @@
|
|||
#include "GCS_Copter.h"
|
||||
#include "Copter.h"
|
||||
|
||||
bool GCS_Copter::cli_enabled() const
|
||||
{
|
||||
#if CLI_ENABLED == ENABLED
|
||||
return copter.g.cli_enabled;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
|
||||
AP_HAL::BetterStream* GCS_Copter::cliSerial() {
|
||||
return copter.cliSerial;
|
||||
}
|
|
@ -0,0 +1,27 @@
|
|||
#pragma once
|
||||
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include "GCS_Mavlink.h"
|
||||
|
||||
class GCS_Copter : public GCS
|
||||
{
|
||||
friend class Copter; // for access to _chan in parameter declarations
|
||||
|
||||
public:
|
||||
|
||||
// return the number of valid GCS objects
|
||||
uint8_t num_gcs() const override { return ARRAY_SIZE(_chan); };
|
||||
|
||||
// return GCS link at offset ofs
|
||||
GCS_MAVLINK_Copter &chan(const uint8_t ofs) override {
|
||||
return _chan[ofs];
|
||||
};
|
||||
|
||||
private:
|
||||
|
||||
GCS_MAVLINK_Copter _chan[MAVLINK_COMM_NUM_BUFFERS];
|
||||
|
||||
bool cli_enabled() const override;
|
||||
AP_HAL::BetterStream* cliSerial() override;
|
||||
|
||||
};
|
|
@ -78,7 +78,7 @@ NOINLINE void Copter::send_heartbeat(mavlink_channel_t chan)
|
|||
// indicate we have set a custom mode
|
||||
base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
||||
|
||||
gcs_chan[chan-MAVLINK_COMM_0].send_heartbeat(get_frame_mav_type(),
|
||||
gcs().chan(chan-MAVLINK_COMM_0).send_heartbeat(get_frame_mav_type(),
|
||||
base_mode,
|
||||
custom_mode,
|
||||
system_status);
|
||||
|
@ -2018,7 +2018,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|||
void Copter::mavlink_delay_cb()
|
||||
{
|
||||
static uint32_t last_1hz, last_50hz, last_5s;
|
||||
if (!gcs_chan[0].initialised || in_mavlink_delay) return;
|
||||
if (!gcs().chan(0).initialised || in_mavlink_delay) return;
|
||||
|
||||
in_mavlink_delay = true;
|
||||
DataFlash.EnableWrites(false);
|
||||
|
@ -2051,11 +2051,7 @@ void Copter::mavlink_delay_cb()
|
|||
*/
|
||||
void Copter::gcs_send_message(enum ap_message id)
|
||||
{
|
||||
for (uint8_t i=0; i<num_gcs; i++) {
|
||||
if (gcs_chan[i].initialised) {
|
||||
gcs_chan[i].send_message(id);
|
||||
}
|
||||
}
|
||||
gcs().send_message(id);
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -2063,12 +2059,7 @@ void Copter::gcs_send_message(enum ap_message id)
|
|||
*/
|
||||
void Copter::gcs_send_mission_item_reached_message(uint16_t mission_index)
|
||||
{
|
||||
for (uint8_t i=0; i<num_gcs; i++) {
|
||||
if (gcs_chan[i].initialised) {
|
||||
gcs_chan[i].mission_item_reached_index = mission_index;
|
||||
gcs_chan[i].send_message(MSG_MISSION_ITEM_REACHED);
|
||||
}
|
||||
}
|
||||
gcs().send_mission_item_reached_message(mission_index);
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -2076,11 +2067,7 @@ void Copter::gcs_send_mission_item_reached_message(uint16_t mission_index)
|
|||
*/
|
||||
void Copter::gcs_data_stream_send(void)
|
||||
{
|
||||
for (uint8_t i=0; i<num_gcs; i++) {
|
||||
if (gcs_chan[i].initialised) {
|
||||
gcs_chan[i].data_stream_send();
|
||||
}
|
||||
}
|
||||
gcs().data_stream_send();
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -2088,15 +2075,7 @@ void Copter::gcs_data_stream_send(void)
|
|||
*/
|
||||
void Copter::gcs_check_input(void)
|
||||
{
|
||||
for (uint8_t i=0; i<num_gcs; i++) {
|
||||
if (gcs_chan[i].initialised) {
|
||||
#if CLI_ENABLED == ENABLED
|
||||
gcs_chan[i].update(g.cli_enabled==1?FUNCTOR_BIND_MEMBER(&Copter::run_cli, void, AP_HAL::UARTDriver *):nullptr);
|
||||
#else
|
||||
gcs_chan[i].update(nullptr);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
gcs().update();
|
||||
}
|
||||
|
||||
void Copter::gcs_send_text(MAV_SEVERITY severity, const char *str)
|
||||
|
|
|
@ -937,9 +937,7 @@ void Copter::log_init(void)
|
|||
{
|
||||
DataFlash.Init(log_structure, ARRAY_SIZE(log_structure));
|
||||
|
||||
for (uint8_t i=0; i<num_gcs; i++) {
|
||||
gcs_chan[i].reset_cli_timeout();
|
||||
}
|
||||
gcs().reset_cli_timeout();
|
||||
}
|
||||
|
||||
#else // LOGGING_ENABLED
|
||||
|
|
|
@ -702,19 +702,19 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
|
||||
// @Group: SR0_
|
||||
// @Path: GCS_Mavlink.cpp
|
||||
GOBJECTN(gcs_chan[0], gcs0, "SR0_", GCS_MAVLINK),
|
||||
GOBJECTN(_gcs._chan[0], gcs0, "SR0_", GCS_MAVLINK),
|
||||
|
||||
// @Group: SR1_
|
||||
// @Path: GCS_Mavlink.cpp
|
||||
GOBJECTN(gcs_chan[1], gcs1, "SR1_", GCS_MAVLINK),
|
||||
GOBJECTN(_gcs._chan[1], gcs1, "SR1_", GCS_MAVLINK),
|
||||
|
||||
// @Group: SR2_
|
||||
// @Path: GCS_Mavlink.cpp
|
||||
GOBJECTN(gcs_chan[2], gcs2, "SR2_", GCS_MAVLINK),
|
||||
GOBJECTN(_gcs._chan[2], gcs2, "SR2_", GCS_MAVLINK),
|
||||
|
||||
// @Group: SR3_
|
||||
// @Path: GCS_Mavlink.cpp
|
||||
GOBJECTN(gcs_chan[3], gcs3, "SR3_", GCS_MAVLINK),
|
||||
GOBJECTN(_gcs._chan[3], gcs3, "SR3_", GCS_MAVLINK),
|
||||
|
||||
// @Group: AHRS_
|
||||
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
|
||||
|
|
|
@ -38,9 +38,11 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||
interference_pct[i] = 0.0f;
|
||||
}
|
||||
|
||||
GCS_MAVLINK_Copter &gcs_chan = gcs().chan(chan-MAVLINK_COMM_0);
|
||||
|
||||
// check compass is enabled
|
||||
if (!g.compass_enabled) {
|
||||
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "Compass disabled");
|
||||
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Compass disabled");
|
||||
ap.compass_mot = false;
|
||||
return MAV_RESULT_TEMPORARILY_REJECTED;
|
||||
}
|
||||
|
@ -49,7 +51,7 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||
compass.read();
|
||||
for (uint8_t i=0; i<compass.get_count(); i++) {
|
||||
if (!compass.healthy(i)) {
|
||||
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "Check compass");
|
||||
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Check compass");
|
||||
ap.compass_mot = false;
|
||||
return MAV_RESULT_TEMPORARILY_REJECTED;
|
||||
}
|
||||
|
@ -58,7 +60,7 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||
// check if radio is calibrated
|
||||
arming.pre_arm_rc_checks(true);
|
||||
if (!ap.pre_arm_rc_check) {
|
||||
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "RC not calibrated");
|
||||
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "RC not calibrated");
|
||||
ap.compass_mot = false;
|
||||
return MAV_RESULT_TEMPORARILY_REJECTED;
|
||||
}
|
||||
|
@ -66,14 +68,14 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||
// check throttle is at zero
|
||||
read_radio();
|
||||
if (channel_throttle->get_control_in() != 0) {
|
||||
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "Throttle not zero");
|
||||
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Throttle not zero");
|
||||
ap.compass_mot = false;
|
||||
return MAV_RESULT_TEMPORARILY_REJECTED;
|
||||
}
|
||||
|
||||
// check we are landed
|
||||
if (!ap.land_complete) {
|
||||
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "Not landed");
|
||||
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Not landed");
|
||||
ap.compass_mot = false;
|
||||
return MAV_RESULT_TEMPORARILY_REJECTED;
|
||||
}
|
||||
|
@ -98,13 +100,13 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||
AP_Notify::flags.esc_calibration = true;
|
||||
|
||||
// warn user we are starting calibration
|
||||
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "Starting calibration");
|
||||
gcs_chan.send_text(MAV_SEVERITY_INFO, "Starting calibration");
|
||||
|
||||
// inform what type of compensation we are attempting
|
||||
if (comp_type == AP_COMPASS_MOT_COMP_CURRENT) {
|
||||
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "Current");
|
||||
gcs_chan.send_text(MAV_SEVERITY_INFO, "Current");
|
||||
} else{
|
||||
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "Throttle");
|
||||
gcs_chan.send_text(MAV_SEVERITY_INFO, "Throttle");
|
||||
}
|
||||
|
||||
// disable throttle and battery failsafe
|
||||
|
@ -250,10 +252,10 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||
}
|
||||
compass.save_motor_compensation();
|
||||
// display success message
|
||||
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "Calibration successful");
|
||||
gcs_chan.send_text(MAV_SEVERITY_INFO, "Calibration successful");
|
||||
} else {
|
||||
// compensation vector never updated, report failure
|
||||
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_NOTICE, "Failed");
|
||||
gcs_chan.send_text(MAV_SEVERITY_NOTICE, "Failed");
|
||||
compass.motor_compensation_type(AP_COMPASS_MOT_COMP_DISABLED);
|
||||
}
|
||||
|
||||
|
|
|
@ -72,28 +72,30 @@ void Copter::motor_test_output()
|
|||
// return true if tests can continue, false if not
|
||||
bool Copter::mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc)
|
||||
{
|
||||
GCS_MAVLINK_Copter &gcs_chan = gcs().chan(chan-MAVLINK_COMM_0);
|
||||
|
||||
// check board has initialised
|
||||
if (!ap.initialised) {
|
||||
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL,"Motor Test: Board initialising");
|
||||
gcs_chan.send_text(MAV_SEVERITY_CRITICAL,"Motor Test: Board initialising");
|
||||
return false;
|
||||
}
|
||||
|
||||
// check rc has been calibrated
|
||||
arming.pre_arm_rc_checks(true);
|
||||
if(check_rc && !ap.pre_arm_rc_check) {
|
||||
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL,"Motor Test: RC not calibrated");
|
||||
gcs_chan.send_text(MAV_SEVERITY_CRITICAL,"Motor Test: RC not calibrated");
|
||||
return false;
|
||||
}
|
||||
|
||||
// ensure we are landed
|
||||
if (!ap.land_complete) {
|
||||
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL,"Motor Test: vehicle not landed");
|
||||
gcs_chan.send_text(MAV_SEVERITY_CRITICAL,"Motor Test: vehicle not landed");
|
||||
return false;
|
||||
}
|
||||
|
||||
// check if safety switch has been pushed
|
||||
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
|
||||
gcs_chan[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL,"Motor Test: Safety switch");
|
||||
gcs_chan.send_text(MAV_SEVERITY_CRITICAL,"Motor Test: Safety switch");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
|
@ -120,7 +120,15 @@ void Copter::init_ardupilot()
|
|||
serial_manager.init();
|
||||
|
||||
// setup first port early to allow BoardConfig to report errors
|
||||
gcs_chan[0].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0);
|
||||
gcs().chan(0).setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0);
|
||||
|
||||
|
||||
#if CLI_ENABLED == ENABLED
|
||||
// specify callback function for CLI menu system
|
||||
if (g.cli_enabled) {
|
||||
gcs().set_run_cli_func(FUNCTOR_BIND_MEMBER(&Copter::run_cli, void, AP_HAL::UARTDriver *));
|
||||
}
|
||||
#endif
|
||||
|
||||
// Register mavlink_delay_cb, which will run anytime you have
|
||||
// more than 5ms remaining in your call to hal.scheduler->delay
|
||||
|
@ -154,9 +162,7 @@ void Copter::init_ardupilot()
|
|||
check_usb_mux();
|
||||
|
||||
// setup telem slots with serial ports
|
||||
for (uint8_t i = 1; i < MAVLINK_COMM_NUM_BUFFERS; i++) {
|
||||
gcs_chan[i].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, i);
|
||||
}
|
||||
gcs().setup_uarts(serial_manager);
|
||||
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
// setup frsky, and pass a number of parameters to the library
|
||||
|
@ -249,16 +255,7 @@ void Copter::init_ardupilot()
|
|||
#endif
|
||||
|
||||
#if CLI_ENABLED == ENABLED
|
||||
if (g.cli_enabled) {
|
||||
const char *msg = "\nPress ENTER 3 times to start interactive setup\n";
|
||||
cliSerial->printf("%s\n", msg);
|
||||
if (gcs_chan[1].initialised && (gcs_chan[1].get_uart() != nullptr)) {
|
||||
gcs_chan[1].get_uart()->printf("%s\n", msg);
|
||||
}
|
||||
if (num_gcs > 2 && gcs_chan[2].initialised && (gcs_chan[2].get_uart() != nullptr)) {
|
||||
gcs_chan[2].get_uart()->printf("%s\n", msg);
|
||||
}
|
||||
}
|
||||
gcs().handle_interactive_setup();
|
||||
#endif // CLI_ENABLED
|
||||
|
||||
#if HIL_MODE != HIL_MODE_DISABLED
|
||||
|
|
Loading…
Reference in New Issue