mirror of https://github.com/ArduPilot/ardupilot
Rover: rename gcs[] to gcs_chan[]
Wish to use gcs() to return the gcs singleton
This commit is contained in:
parent
49bf336539
commit
407e251e1d
|
@ -63,7 +63,7 @@ void Rover::send_heartbeat(mavlink_channel_t chan)
|
|||
// indicate we have set a custom mode
|
||||
base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
||||
|
||||
gcs[chan-MAVLINK_COMM_0].send_heartbeat(MAV_TYPE_GROUND_ROVER,
|
||||
gcs_chan[chan-MAVLINK_COMM_0].send_heartbeat(MAV_TYPE_GROUND_ROVER,
|
||||
base_mode,
|
||||
custom_mode,
|
||||
system_status);
|
||||
|
@ -1485,7 +1485,7 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
void Rover::mavlink_delay_cb()
|
||||
{
|
||||
static uint32_t last_1hz, last_50hz, last_5s;
|
||||
if (!gcs[0].initialised || in_mavlink_delay) {
|
||||
if (!gcs_chan[0].initialised || in_mavlink_delay) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -1518,8 +1518,8 @@ void Rover::mavlink_delay_cb()
|
|||
void Rover::gcs_send_message(enum ap_message id)
|
||||
{
|
||||
for (uint8_t i=0; i < num_gcs; i++) {
|
||||
if (gcs[i].initialised) {
|
||||
gcs[i].send_message(id);
|
||||
if (gcs_chan[i].initialised) {
|
||||
gcs_chan[i].send_message(id);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -1530,9 +1530,9 @@ void Rover::gcs_send_message(enum ap_message id)
|
|||
void Rover::gcs_send_mission_item_reached_message(uint16_t mission_index)
|
||||
{
|
||||
for (uint8_t i=0; i < num_gcs; i++) {
|
||||
if (gcs[i].initialised) {
|
||||
gcs[i].mission_item_reached_index = mission_index;
|
||||
gcs[i].send_message(MSG_MISSION_ITEM_REACHED);
|
||||
if (gcs_chan[i].initialised) {
|
||||
gcs_chan[i].mission_item_reached_index = mission_index;
|
||||
gcs_chan[i].send_message(MSG_MISSION_ITEM_REACHED);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -1543,8 +1543,8 @@ void Rover::gcs_send_mission_item_reached_message(uint16_t mission_index)
|
|||
void Rover::gcs_data_stream_send(void)
|
||||
{
|
||||
for (uint8_t i=0; i < num_gcs; i++) {
|
||||
if (gcs[i].initialised) {
|
||||
gcs[i].data_stream_send();
|
||||
if (gcs_chan[i].initialised) {
|
||||
gcs_chan[i].data_stream_send();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -1555,11 +1555,11 @@ void Rover::gcs_data_stream_send(void)
|
|||
void Rover::gcs_update(void)
|
||||
{
|
||||
for (uint8_t i=0; i < num_gcs; i++) {
|
||||
if (gcs[i].initialised) {
|
||||
if (gcs_chan[i].initialised) {
|
||||
#if CLI_ENABLED == ENABLED
|
||||
gcs[i].update(g.cli_enabled == 1 ? FUNCTOR_BIND_MEMBER(&Rover::run_cli, void, AP_HAL::UARTDriver *) : nullptr);
|
||||
gcs_chan[i].update(g.cli_enabled == 1 ? FUNCTOR_BIND_MEMBER(&Rover::run_cli, void, AP_HAL::UARTDriver *) : nullptr);
|
||||
#else
|
||||
gcs[i].update(nullptr);
|
||||
gcs_chan[i].update(nullptr);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
|
|
@ -469,7 +469,7 @@ void Rover::log_init(void)
|
|||
DataFlash.Prep();
|
||||
gcs_send_text(MAV_SEVERITY_INFO, "Prepared log system");
|
||||
for (uint8_t i=0; i < num_gcs; i++) {
|
||||
gcs[i].reset_cli_timeout();
|
||||
gcs_chan[i].reset_cli_timeout();
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -408,19 +408,19 @@ const AP_Param::Info Rover::var_info[] = {
|
|||
|
||||
// @Group: SR0_
|
||||
// @Path: GCS_Mavlink.cpp
|
||||
GOBJECTN(gcs[0], gcs0, "SR0_", GCS_MAVLINK),
|
||||
GOBJECTN(gcs_chan[0], gcs0, "SR0_", GCS_MAVLINK),
|
||||
|
||||
// @Group: SR1_
|
||||
// @Path: GCS_Mavlink.cpp
|
||||
GOBJECTN(gcs[1], gcs1, "SR1_", GCS_MAVLINK),
|
||||
GOBJECTN(gcs_chan[1], gcs1, "SR1_", GCS_MAVLINK),
|
||||
|
||||
// @Group: SR2_
|
||||
// @Path: GCS_Mavlink.cpp
|
||||
GOBJECTN(gcs[2], gcs2, "SR2_", GCS_MAVLINK),
|
||||
GOBJECTN(gcs_chan[2], gcs2, "SR2_", GCS_MAVLINK),
|
||||
|
||||
// @Group: SR3_
|
||||
// @Path: GCS_Mavlink.cpp
|
||||
GOBJECTN(gcs[3], gcs3, "SR3_", GCS_MAVLINK),
|
||||
GOBJECTN(gcs_chan[3], gcs3, "SR3_", GCS_MAVLINK),
|
||||
|
||||
// @Group: SERIAL
|
||||
// @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp
|
||||
|
|
|
@ -185,7 +185,7 @@ private:
|
|||
// GCS handling
|
||||
AP_SerialManager serial_manager;
|
||||
const uint8_t num_gcs;
|
||||
GCS_MAVLINK_Rover gcs[MAVLINK_COMM_NUM_BUFFERS];
|
||||
GCS_MAVLINK_Rover gcs_chan[MAVLINK_COMM_NUM_BUFFERS];
|
||||
|
||||
// relay support
|
||||
AP_Relay relay;
|
||||
|
|
|
@ -100,7 +100,7 @@ void Rover::init_ardupilot()
|
|||
serial_manager.init();
|
||||
|
||||
// setup first port early to allow BoardConfig to report errors
|
||||
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
|
||||
// more than 5ms remaining in your call to hal.scheduler->delay
|
||||
|
@ -133,7 +133,7 @@ void Rover::init_ardupilot()
|
|||
|
||||
// setup telem slots with serial ports
|
||||
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 telemetry
|
||||
|
@ -193,11 +193,11 @@ void Rover::init_ardupilot()
|
|||
if (g.cli_enabled == 1) {
|
||||
const char *msg = "\nPress ENTER 3 times to start interactive setup\n";
|
||||
cliSerial->printf("%s\n", msg);
|
||||
if (gcs[1].initialised && (gcs[1].get_uart() != nullptr)) {
|
||||
gcs[1].get_uart()->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[2].initialised && (gcs[2].get_uart() != nullptr)) {
|
||||
gcs[2].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);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue