mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Plane: rename gcs[] to gcs_chan[]
Wish to use gcs() to return the gcs singleton
This commit is contained in:
parent
029aeeb4fd
commit
d060670ba3
@ -91,7 +91,7 @@ void Plane::send_heartbeat(mavlink_channel_t chan)
|
|||||||
// indicate we have set a custom mode
|
// indicate we have set a custom mode
|
||||||
base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
||||||
|
|
||||||
gcs[chan-MAVLINK_COMM_0].send_heartbeat(MAV_TYPE_FIXED_WING,
|
gcs_chan[chan-MAVLINK_COMM_0].send_heartbeat(MAV_TYPE_FIXED_WING,
|
||||||
base_mode,
|
base_mode,
|
||||||
custom_mode,
|
custom_mode,
|
||||||
system_status);
|
system_status);
|
||||||
@ -2098,7 +2098,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
|||||||
void Plane::mavlink_delay_cb()
|
void Plane::mavlink_delay_cb()
|
||||||
{
|
{
|
||||||
static uint32_t last_1hz, last_50hz, last_5s;
|
static uint32_t last_1hz, last_50hz, last_5s;
|
||||||
if (!gcs[0].initialised || in_mavlink_delay) return;
|
if (!gcs_chan[0].initialised || in_mavlink_delay) return;
|
||||||
|
|
||||||
in_mavlink_delay = true;
|
in_mavlink_delay = true;
|
||||||
|
|
||||||
@ -2129,8 +2129,8 @@ void Plane::mavlink_delay_cb()
|
|||||||
void Plane::gcs_send_message(enum ap_message id)
|
void Plane::gcs_send_message(enum ap_message id)
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<num_gcs; i++) {
|
for (uint8_t i=0; i<num_gcs; i++) {
|
||||||
if (gcs[i].initialised) {
|
if (gcs_chan[i].initialised) {
|
||||||
gcs[i].send_message(id);
|
gcs_chan[i].send_message(id);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -2141,9 +2141,9 @@ void Plane::gcs_send_message(enum ap_message id)
|
|||||||
void Plane::gcs_send_mission_item_reached_message(uint16_t mission_index)
|
void Plane::gcs_send_mission_item_reached_message(uint16_t mission_index)
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<num_gcs; i++) {
|
for (uint8_t i=0; i<num_gcs; i++) {
|
||||||
if (gcs[i].initialised) {
|
if (gcs_chan[i].initialised) {
|
||||||
gcs[i].mission_item_reached_index = mission_index;
|
gcs_chan[i].mission_item_reached_index = mission_index;
|
||||||
gcs[i].send_message(MSG_MISSION_ITEM_REACHED);
|
gcs_chan[i].send_message(MSG_MISSION_ITEM_REACHED);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -2154,8 +2154,8 @@ void Plane::gcs_send_mission_item_reached_message(uint16_t mission_index)
|
|||||||
void Plane::gcs_data_stream_send(void)
|
void Plane::gcs_data_stream_send(void)
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<num_gcs; i++) {
|
for (uint8_t i=0; i<num_gcs; i++) {
|
||||||
if (gcs[i].initialised) {
|
if (gcs_chan[i].initialised) {
|
||||||
gcs[i].data_stream_send();
|
gcs_chan[i].data_stream_send();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -2166,11 +2166,11 @@ void Plane::gcs_data_stream_send(void)
|
|||||||
void Plane::gcs_update(void)
|
void Plane::gcs_update(void)
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<num_gcs; i++) {
|
for (uint8_t i=0; i<num_gcs; i++) {
|
||||||
if (gcs[i].initialised) {
|
if (gcs_chan[i].initialised) {
|
||||||
#if CLI_ENABLED == ENABLED
|
#if CLI_ENABLED == ENABLED
|
||||||
gcs[i].update(g.cli_enabled == 1 ? FUNCTOR_BIND_MEMBER(&Plane::run_cli, void, AP_HAL::UARTDriver *):nullptr);
|
gcs_chan[i].update(g.cli_enabled == 1 ? FUNCTOR_BIND_MEMBER(&Plane::run_cli, void, AP_HAL::UARTDriver *):nullptr);
|
||||||
#else
|
#else
|
||||||
gcs[i].update(nullptr);
|
gcs_chan[i].update(nullptr);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -2204,7 +2204,7 @@ void Plane::gcs_send_text_fmt(MAV_SEVERITY severity, const char *fmt, ...)
|
|||||||
void Plane::gcs_send_airspeed_calibration(const Vector3f &vg)
|
void Plane::gcs_send_airspeed_calibration(const Vector3f &vg)
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<num_gcs; i++) {
|
for (uint8_t i=0; i<num_gcs; i++) {
|
||||||
if (gcs[i].initialised) {
|
if (gcs_chan[i].initialised) {
|
||||||
if (HAVE_PAYLOAD_SPACE((mavlink_channel_t)i, AIRSPEED_AUTOCAL)) {
|
if (HAVE_PAYLOAD_SPACE((mavlink_channel_t)i, AIRSPEED_AUTOCAL)) {
|
||||||
airspeed.log_mavlink_send((mavlink_channel_t)i, vg);
|
airspeed.log_mavlink_send((mavlink_channel_t)i, vg);
|
||||||
}
|
}
|
||||||
|
@ -543,7 +543,7 @@ void Plane::log_init(void)
|
|||||||
DataFlash.Prep();
|
DataFlash.Prep();
|
||||||
gcs_send_text(MAV_SEVERITY_INFO, "Prepared log system");
|
gcs_send_text(MAV_SEVERITY_INFO, "Prepared log system");
|
||||||
for (uint8_t i=0; i<num_gcs; i++) {
|
for (uint8_t i=0; i<num_gcs; i++) {
|
||||||
gcs[i].reset_cli_timeout();
|
gcs_chan[i].reset_cli_timeout();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1070,19 +1070,19 @@ const AP_Param::Info Plane::var_info[] = {
|
|||||||
|
|
||||||
// @Group: SR0_
|
// @Group: SR0_
|
||||||
// @Path: GCS_Mavlink.cpp
|
// @Path: GCS_Mavlink.cpp
|
||||||
GOBJECTN(gcs[0], gcs0, "SR0_", GCS_MAVLINK),
|
GOBJECTN(gcs_chan[0], gcs0, "SR0_", GCS_MAVLINK),
|
||||||
|
|
||||||
// @Group: SR1_
|
// @Group: SR1_
|
||||||
// @Path: GCS_Mavlink.cpp
|
// @Path: GCS_Mavlink.cpp
|
||||||
GOBJECTN(gcs[1], gcs1, "SR1_", GCS_MAVLINK),
|
GOBJECTN(gcs_chan[1], gcs1, "SR1_", GCS_MAVLINK),
|
||||||
|
|
||||||
// @Group: SR2_
|
// @Group: SR2_
|
||||||
// @Path: GCS_Mavlink.cpp
|
// @Path: GCS_Mavlink.cpp
|
||||||
GOBJECTN(gcs[2], gcs2, "SR2_", GCS_MAVLINK),
|
GOBJECTN(gcs_chan[2], gcs2, "SR2_", GCS_MAVLINK),
|
||||||
|
|
||||||
// @Group: SR3_
|
// @Group: SR3_
|
||||||
// @Path: GCS_Mavlink.cpp
|
// @Path: GCS_Mavlink.cpp
|
||||||
GOBJECTN(gcs[3], gcs3, "SR3_", GCS_MAVLINK),
|
GOBJECTN(gcs_chan[3], gcs3, "SR3_", GCS_MAVLINK),
|
||||||
|
|
||||||
// @Group: INS_
|
// @Group: INS_
|
||||||
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
|
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
|
||||||
|
@ -251,7 +251,7 @@ private:
|
|||||||
// GCS selection
|
// GCS selection
|
||||||
AP_SerialManager serial_manager;
|
AP_SerialManager serial_manager;
|
||||||
const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS;
|
const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS;
|
||||||
GCS_MAVLINK_Plane gcs[MAVLINK_COMM_NUM_BUFFERS];
|
GCS_MAVLINK_Plane gcs_chan[MAVLINK_COMM_NUM_BUFFERS];
|
||||||
|
|
||||||
// selected navigation controller
|
// selected navigation controller
|
||||||
AP_Navigation *nav_controller = &L1_controller;
|
AP_Navigation *nav_controller = &L1_controller;
|
||||||
|
@ -122,7 +122,7 @@ void Plane::init_ardupilot()
|
|||||||
|
|
||||||
// initialise serial ports
|
// initialise serial ports
|
||||||
serial_manager.init();
|
serial_manager.init();
|
||||||
gcs[0].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0);
|
gcs_chan[0].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0);
|
||||||
|
|
||||||
// Register mavlink_delay_cb, which will run anytime you have
|
// Register mavlink_delay_cb, which will run anytime you have
|
||||||
// more than 5ms remaining in your call to hal.scheduler->delay
|
// more than 5ms remaining in your call to hal.scheduler->delay
|
||||||
@ -162,7 +162,7 @@ void Plane::init_ardupilot()
|
|||||||
|
|
||||||
// setup telem slots with serial ports
|
// setup telem slots with serial ports
|
||||||
for (uint8_t i = 1; i < MAVLINK_COMM_NUM_BUFFERS; i++) {
|
for (uint8_t i = 1; i < MAVLINK_COMM_NUM_BUFFERS; i++) {
|
||||||
gcs[i].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, i);
|
gcs_chan[i].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, i);
|
||||||
}
|
}
|
||||||
|
|
||||||
// setup frsky
|
// setup frsky
|
||||||
@ -232,11 +232,11 @@ void Plane::init_ardupilot()
|
|||||||
if (g.cli_enabled == 1) {
|
if (g.cli_enabled == 1) {
|
||||||
const char *msg = "\nPress ENTER 3 times to start interactive setup\n";
|
const char *msg = "\nPress ENTER 3 times to start interactive setup\n";
|
||||||
cliSerial->printf("%s\n", msg);
|
cliSerial->printf("%s\n", msg);
|
||||||
if (gcs[1].initialised && (gcs[1].get_uart() != nullptr)) {
|
if (gcs_chan[1].initialised && (gcs_chan[1].get_uart() != nullptr)) {
|
||||||
gcs[1].get_uart()->printf("%s\n", msg);
|
gcs_chan[1].get_uart()->printf("%s\n", msg);
|
||||||
}
|
}
|
||||||
if (num_gcs > 2 && gcs[2].initialised && (gcs[2].get_uart() != nullptr)) {
|
if (num_gcs > 2 && gcs_chan[2].initialised && (gcs_chan[2].get_uart() != nullptr)) {
|
||||||
gcs[2].get_uart()->printf("%s\n", msg);
|
gcs_chan[2].get_uart()->printf("%s\n", msg);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif // CLI_ENABLED
|
#endif // CLI_ENABLED
|
||||||
@ -571,8 +571,8 @@ void Plane::check_long_failsafe()
|
|||||||
(tnow - failsafe.last_heartbeat_ms) > g.long_fs_timeout*1000) {
|
(tnow - failsafe.last_heartbeat_ms) > g.long_fs_timeout*1000) {
|
||||||
failsafe_long_on_event(FAILSAFE_GCS, MODE_REASON_GCS_FAILSAFE);
|
failsafe_long_on_event(FAILSAFE_GCS, MODE_REASON_GCS_FAILSAFE);
|
||||||
} else if (g.gcs_heartbeat_fs_enabled == GCS_FAILSAFE_HB_RSSI &&
|
} else if (g.gcs_heartbeat_fs_enabled == GCS_FAILSAFE_HB_RSSI &&
|
||||||
gcs[0].last_radio_status_remrssi_ms != 0 &&
|
gcs_chan[0].last_radio_status_remrssi_ms != 0 &&
|
||||||
(tnow - gcs[0].last_radio_status_remrssi_ms) > g.long_fs_timeout*1000) {
|
(tnow - gcs_chan[0].last_radio_status_remrssi_ms) > g.long_fs_timeout*1000) {
|
||||||
failsafe_long_on_event(FAILSAFE_GCS, MODE_REASON_GCS_FAILSAFE);
|
failsafe_long_on_event(FAILSAFE_GCS, MODE_REASON_GCS_FAILSAFE);
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
|
Loading…
Reference in New Issue
Block a user