mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 17:18:28 -04:00
GCS_Console: remove GCS_Console
This commit is contained in:
parent
d650b4eaa7
commit
aba525e4c5
@ -1,50 +0,0 @@
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "GCS_Console.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
void gcs_console_handle_data16(mavlink_message_t* msg) {
|
||||
|
||||
mavlink_data16_t data16;
|
||||
mavlink_msg_data16_decode(msg, &data16);
|
||||
if (data16.type == DATAMSG_TYPE_CONSOLE) {
|
||||
hal.console->backend_write(data16.data, data16.len);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void gcs_console_handle_data32(mavlink_message_t* msg) {
|
||||
|
||||
mavlink_data32_t data32;
|
||||
mavlink_msg_data32_decode(msg, &data32);
|
||||
if (data32.type == DATAMSG_TYPE_CONSOLE) {
|
||||
hal.console->backend_write(data32.data, data32.len);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void gcs_console_send(mavlink_channel_t chan) {
|
||||
uint8_t cons[32];
|
||||
memset(cons, 0, 32);
|
||||
int16_t txspace = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
/* There are two bytes of overhead per packet (on top of the non payload
|
||||
* bytes). We can read up to 32 bytes from the console if we have 34
|
||||
* available for tx, up to 16 bytes if we have more than 18 available.
|
||||
* otherwise we have to try again later. */
|
||||
int readable = 32;
|
||||
if (txspace >= 18 && txspace < 34) {
|
||||
readable = 16;
|
||||
} else if ( txspace < 18 ) {
|
||||
return;
|
||||
}
|
||||
/* Read from the console backend */
|
||||
int avail = hal.console->backend_read(cons, readable);
|
||||
/* Send in the smallest packet available. (Don't send if 0.) */
|
||||
if (avail > 0 && avail <= 16) {
|
||||
mavlink_msg_data16_send(chan, DATAMSG_TYPE_CONSOLE, avail, cons);
|
||||
} else if (avail > 16 && avail <= 32) {
|
||||
mavlink_msg_data32_send(chan, DATAMSG_TYPE_CONSOLE, avail, cons);
|
||||
}
|
||||
}
|
||||
|
@ -1,21 +0,0 @@
|
||||
#pragma once
|
||||
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
|
||||
/* Ensure compatibility with GCS_MAVLink library. We need the DATA16
|
||||
* and DATA32 mesages. If these aren't present, get them from the mavlink
|
||||
* repo message_definitions/ardupilotmega.xml and regenerate the GCS_MAVLink
|
||||
* definitions. */
|
||||
#ifndef MAVLINK_MSG_ID_DATA16
|
||||
#error GCS_Console module requires Mavlink Message DATA16
|
||||
#endif
|
||||
#ifndef MAVLINK_MSG_ID_DATA32
|
||||
#error GCS_Console module requires Mavlink Message DATA32
|
||||
#endif
|
||||
|
||||
#define DATAMSG_TYPE_CONSOLE 0xFE
|
||||
|
||||
void gcs_console_handle_data16(mavlink_message_t* msg);
|
||||
void gcs_console_handle_data32(mavlink_message_t* msg);
|
||||
|
||||
void gcs_console_send(mavlink_channel_t chan);
|
@ -1,64 +0,0 @@
|
||||
// This code is placed into the public domain.
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <AP_Mission/AP_Mission.h>
|
||||
#include <StorageManager/StorageManager.h>
|
||||
#include <AP_Terrain/AP_Terrain.h>
|
||||
#include <GCS_Console/GCS_Console.h>
|
||||
|
||||
#include "simplegcs.h"
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
void flush_console_to_statustext() {
|
||||
uint8_t data[50];
|
||||
int n = hal.console->backend_read(data, 50);
|
||||
if (n > 0) {
|
||||
try_send_statustext(MAVLINK_COMM_0, (char*) data, n);
|
||||
}
|
||||
}
|
||||
|
||||
void console_loopback() {
|
||||
int a = hal.console->available();
|
||||
if (a > 0) {
|
||||
hal.console->printf("Console loopback:");
|
||||
int r = hal.console->read();
|
||||
while (r > 0) {
|
||||
hal.console->write( (uint8_t) r );
|
||||
r = hal.console->read();
|
||||
}
|
||||
hal.console->printf("\n");
|
||||
}
|
||||
}
|
||||
|
||||
void setup(void) {
|
||||
/* Allocate large enough buffers on uartA to support mavlink */
|
||||
hal.uartA->begin(115200, 128, 256);
|
||||
|
||||
/* Setup GCS_Mavlink library's comm 0 port. */
|
||||
mavlink_comm_port[0] = hal.uartA;
|
||||
|
||||
char hello[] = "Hello statustext\r\n";
|
||||
try_send_statustext(MAVLINK_COMM_0, hello, strlen(hello));
|
||||
|
||||
hal.console->backend_open();
|
||||
hal.console->printf("Hello hal.console\r\n");
|
||||
}
|
||||
|
||||
int i = 0;
|
||||
void loop(void) {
|
||||
try_send_message(MAVLINK_COMM_0, MAVLINK_MSG_ID_HEARTBEAT);
|
||||
simplegcs_update(MAVLINK_COMM_0);
|
||||
// flush_console_to_statustext();
|
||||
gcs_console_send(MAVLINK_COMM_0);
|
||||
|
||||
console_loopback();
|
||||
hal.scheduler->delay(100);
|
||||
}
|
||||
|
||||
AP_HAL_MAIN();
|
@ -1,98 +0,0 @@
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <GCS_Console/GCS_Console.h>
|
||||
#include "simplegcs.h"
|
||||
|
||||
void send_heartbeat(mavlink_channel_t chan) {
|
||||
uint8_t base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED
|
||||
| MAV_MODE_FLAG_GUIDED_ENABLED
|
||||
| MAV_MODE_FLAG_SAFETY_ARMED
|
||||
| MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
||||
uint8_t system_status = MAV_STATE_ACTIVE;
|
||||
uint32_t custom_mode = 5 ; /* Loiter is mode 5. */
|
||||
|
||||
mavlink_msg_heartbeat_send(
|
||||
chan,
|
||||
MAV_TYPE_QUADROTOR,
|
||||
MAV_AUTOPILOT_ARDUPILOTMEGA,
|
||||
base_mode,
|
||||
custom_mode,
|
||||
system_status);
|
||||
}
|
||||
|
||||
#define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_ ## id ## _LEN) return false
|
||||
|
||||
bool try_send_message(mavlink_channel_t chan, int msgid) {
|
||||
|
||||
int payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
|
||||
switch (msgid) {
|
||||
case MAVLINK_MSG_ID_HEARTBEAT:
|
||||
CHECK_PAYLOAD_SIZE(HEARTBEAT);
|
||||
send_heartbeat(chan);
|
||||
return true;
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
bool try_send_statustext(mavlink_channel_t chan, const char *text, int len) {
|
||||
|
||||
int payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
CHECK_PAYLOAD_SIZE(STATUSTEXT);
|
||||
|
||||
char statustext[50] = { 0 };
|
||||
if (len < 50) {
|
||||
memcpy(statustext, text, len);
|
||||
}
|
||||
mavlink_msg_statustext_send(
|
||||
chan,
|
||||
4, /* MAV_SEVERITY_WARNING */
|
||||
statustext);
|
||||
return true;
|
||||
}
|
||||
// -----------------------------------------------------------------------
|
||||
|
||||
|
||||
void simplegcs_update(mavlink_channel_t chan) {
|
||||
mavlink_message_t msg;
|
||||
mavlink_status_t status;
|
||||
while(comm_get_available(chan)){
|
||||
uint8_t c = comm_receive_ch(chan);
|
||||
bool newmsg = mavlink_parse_char(chan, c, &msg, &status);
|
||||
if (newmsg) {
|
||||
handle_message(chan, &msg);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void handle_message(mavlink_channel_t chan, mavlink_message_t* msg) {
|
||||
hal.console->printf("SimpleGCS Handle Message %d\r\n", msg->msgid);
|
||||
switch (msg->msgid) {
|
||||
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
|
||||
{
|
||||
char param_name[16] = "NOPARAMS";
|
||||
|
||||
/* Send a single parameter.*/
|
||||
mavlink_msg_param_value_send(
|
||||
chan,
|
||||
param_name,
|
||||
0.0f, /* param value */
|
||||
MAVLINK_TYPE_FLOAT, /* param type */
|
||||
1, /* _queued_parameter_count */
|
||||
0); /* _queued_parameter_index */
|
||||
break;
|
||||
}
|
||||
case MAVLINK_MSG_ID_DATA16:
|
||||
gcs_console_handle_data16(msg);
|
||||
break;
|
||||
case MAVLINK_MSG_ID_DATA32:
|
||||
gcs_console_handle_data32(msg);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
@ -1,10 +0,0 @@
|
||||
#pragma once
|
||||
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
|
||||
void send_heartbeat(mavlink_channel_t chan);
|
||||
bool try_send_message(mavlink_channel_t chan, int msgid);
|
||||
bool try_send_statustext(mavlink_channel_t chan, const char *text, int len);
|
||||
|
||||
void simplegcs_update(mavlink_channel_t chan);
|
||||
void handle_message(mavlink_channel_t chan, mavlink_message_t* msg);
|
@ -1,10 +0,0 @@
|
||||
#!/usr/bin/env python
|
||||
# encoding: utf-8
|
||||
|
||||
def build(bld):
|
||||
# TODO: Test code doesn't build. Fix or delete the test.
|
||||
return
|
||||
|
||||
bld.ap_example(
|
||||
use='ap',
|
||||
)
|
Loading…
Reference in New Issue
Block a user