mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 01:48:29 -04:00
Plane: updates for new GCS_MAVLink API
This commit is contained in:
parent
2b44d33694
commit
511e8beaed
@ -6,9 +6,6 @@
|
|||||||
// use this to prevent recursion during sensor init
|
// use this to prevent recursion during sensor init
|
||||||
static bool in_mavlink_delay;
|
static bool in_mavlink_delay;
|
||||||
|
|
||||||
// true when we have received at least 1 MAVLink packet
|
|
||||||
static bool mavlink_active;
|
|
||||||
|
|
||||||
// true if we are out of time in our event timeslice
|
// true if we are out of time in our event timeslice
|
||||||
static bool gcs_out_of_time;
|
static bool gcs_out_of_time;
|
||||||
|
|
||||||
@ -914,65 +911,6 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] PROGMEM = {
|
|||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
void
|
|
||||||
GCS_MAVLINK::update(void)
|
|
||||||
{
|
|
||||||
// receive new packets
|
|
||||||
mavlink_message_t msg;
|
|
||||||
mavlink_status_t status;
|
|
||||||
status.packet_rx_drop_count = 0;
|
|
||||||
|
|
||||||
// process received bytes
|
|
||||||
uint16_t nbytes = comm_get_available(chan);
|
|
||||||
for (uint16_t i=0; i<nbytes; i++)
|
|
||||||
{
|
|
||||||
uint8_t c = comm_receive_ch(chan);
|
|
||||||
|
|
||||||
#if CLI_ENABLED == ENABLED
|
|
||||||
/* allow CLI to be started by hitting enter 3 times, if no
|
|
||||||
* heartbeat packets have been received */
|
|
||||||
if (mavlink_active == 0 && (millis() - _cli_timeout) < 20000 &&
|
|
||||||
comm_is_idle(chan)) {
|
|
||||||
if (c == '\n' || c == '\r') {
|
|
||||||
crlf_count++;
|
|
||||||
} else {
|
|
||||||
crlf_count = 0;
|
|
||||||
}
|
|
||||||
if (crlf_count == 3) {
|
|
||||||
run_cli(_port);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Try to get a new message
|
|
||||||
if (mavlink_parse_char(chan, c, &msg, &status)) {
|
|
||||||
// we exclude radio packets to make it possible to use the
|
|
||||||
// CLI over the radio
|
|
||||||
if (msg.msgid != MAVLINK_MSG_ID_RADIO && msg.msgid != MAVLINK_MSG_ID_RADIO_STATUS) {
|
|
||||||
mavlink_active = true;
|
|
||||||
}
|
|
||||||
handleMessage(&msg);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!waypoint_receiving) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t tnow = millis();
|
|
||||||
|
|
||||||
if (waypoint_receiving &&
|
|
||||||
waypoint_request_i <= waypoint_request_last &&
|
|
||||||
tnow - waypoint_timelast_request > 2000U + (stream_slowdown*20)) {
|
|
||||||
waypoint_timelast_request = tnow;
|
|
||||||
send_message(MSG_NEXT_WAYPOINT);
|
|
||||||
}
|
|
||||||
|
|
||||||
// stop waypoint receiving if timeout
|
|
||||||
if (waypoint_receiving && (millis() - waypoint_timelast_receive) > waypoint_receive_timeout) {
|
|
||||||
waypoint_receiving = false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// see if we should send a stream now. Called at 50Hz
|
// see if we should send a stream now. Called at 50Hz
|
||||||
bool GCS_MAVLINK::stream_trigger(enum streams stream_num)
|
bool GCS_MAVLINK::stream_trigger(enum streams stream_num)
|
||||||
@ -1777,7 +1715,11 @@ static void 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[i].initialised) {
|
||||||
gcs[i].update();
|
#if CLI_ENABLED == ENABLED
|
||||||
|
gcs[i].update(run_cli);
|
||||||
|
#else
|
||||||
|
gcs[i].update(NULL);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -95,7 +95,7 @@ static void init_ardupilot()
|
|||||||
set_control_channels();
|
set_control_channels();
|
||||||
|
|
||||||
// reset the uartA baud rate after parameter load
|
// reset the uartA baud rate after parameter load
|
||||||
hal.uartA->begin(map_baudrate(g.serial0_baud, SERIAL0_BAUD));
|
hal.uartA->begin(map_baudrate(g.serial0_baud));
|
||||||
|
|
||||||
// keep a record of how many resets have happened. This can be
|
// keep a record of how many resets have happened. This can be
|
||||||
// used to detect in-flight resets
|
// used to detect in-flight resets
|
||||||
@ -116,10 +116,10 @@ static void init_ardupilot()
|
|||||||
check_usb_mux();
|
check_usb_mux();
|
||||||
|
|
||||||
// we have a 2nd serial port for telemetry
|
// we have a 2nd serial port for telemetry
|
||||||
gcs[1].setup_uart(hal.uartC, map_baudrate(g.serial1_baud, SERIAL1_BAUD), 128, SERIAL1_BUFSIZE);
|
gcs[1].setup_uart(hal.uartC, map_baudrate(g.serial1_baud), 128, SERIAL1_BUFSIZE);
|
||||||
|
|
||||||
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
||||||
gcs[2].setup_uart(hal.uartD, map_baudrate(g.serial2_baud, SERIAL2_BAUD), 128, SERIAL2_BUFSIZE);
|
gcs[2].setup_uart(hal.uartD, map_baudrate(g.serial2_baud), 128, SERIAL2_BUFSIZE);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
mavlink_system.sysid = g.sysid_this_mav;
|
mavlink_system.sysid = g.sysid_this_mav;
|
||||||
@ -499,27 +499,6 @@ static void resetPerfData(void) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
* map from a 8 bit EEPROM baud rate to a real baud rate
|
|
||||||
*/
|
|
||||||
static uint32_t map_baudrate(int8_t rate, uint32_t default_baud)
|
|
||||||
{
|
|
||||||
switch (rate) {
|
|
||||||
case 1: return 1200;
|
|
||||||
case 2: return 2400;
|
|
||||||
case 4: return 4800;
|
|
||||||
case 9: return 9600;
|
|
||||||
case 19: return 19200;
|
|
||||||
case 38: return 38400;
|
|
||||||
case 57: return 57600;
|
|
||||||
case 111: return 111100;
|
|
||||||
case 115: return 115200;
|
|
||||||
}
|
|
||||||
cliSerial->println_P(PSTR("Invalid baudrate"));
|
|
||||||
return default_baud;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
static void check_usb_mux(void)
|
static void check_usb_mux(void)
|
||||||
{
|
{
|
||||||
bool usb_check = hal.gpio->usb_connected();
|
bool usb_check = hal.gpio->usb_connected();
|
||||||
@ -538,7 +517,7 @@ static void check_usb_mux(void)
|
|||||||
if (usb_connected) {
|
if (usb_connected) {
|
||||||
hal.uartA->begin(SERIAL0_BAUD);
|
hal.uartA->begin(SERIAL0_BAUD);
|
||||||
} else {
|
} else {
|
||||||
hal.uartA->begin(map_baudrate(g.serial1_baud, SERIAL1_BAUD));
|
hal.uartA->begin(map_baudrate(g.serial1_baud));
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user