mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Copter: make all message output csv
This commit is contained in:
parent
d2767b911c
commit
fb1358a629
@ -256,7 +256,7 @@ static void Log_Read_GPS()
|
||||
print_latlon(cliSerial, pkt.latitude);
|
||||
cliSerial->print_P(PSTR(", "));
|
||||
print_latlon(cliSerial, pkt.longitude);
|
||||
cliSerial->printf_P(PSTR(", %4.4f, %4.4f, %d, %ld\n"),
|
||||
cliSerial->printf_P(PSTR(", %4.4f, %4.4f, %lu, %ld\n"),
|
||||
pkt.rel_altitude*0.01,
|
||||
pkt.altitude*0.01,
|
||||
(unsigned long)pkt.ground_speed,
|
||||
@ -488,7 +488,7 @@ static void Log_Read_Optflow()
|
||||
|
||||
struct log_Nav_Tuning {
|
||||
LOG_PACKET_HEADER;
|
||||
int16_t wp_distance;
|
||||
uint32_t wp_distance;
|
||||
int16_t wp_bearing;
|
||||
int16_t lat_error;
|
||||
int16_t lon_error;
|
||||
@ -503,7 +503,7 @@ static void Log_Write_Nav_Tuning()
|
||||
{
|
||||
struct log_Nav_Tuning pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_NAV_TUNING_MSG),
|
||||
wp_distance : (int16_t) wp_distance,
|
||||
wp_distance : wp_distance,
|
||||
wp_bearing : (int16_t) (wp_bearing/100),
|
||||
lat_error : (int16_t) lat_error,
|
||||
lon_error : (int16_t) long_error,
|
||||
@ -522,8 +522,8 @@ static void Log_Read_Nav_Tuning()
|
||||
DataFlash.ReadPacket(&pkt, sizeof(pkt));
|
||||
|
||||
// 1 2 3 4 5 6 7 8
|
||||
cliSerial->printf_P(PSTR("NTUN, %d, %d, %d, %d, %d, %d, %d, %d\n"),
|
||||
(int)pkt.wp_distance,
|
||||
cliSerial->printf_P(PSTR("NTUN, %lu, %d, %d, %d, %d, %d, %d, %d\n"),
|
||||
(unsigned long)pkt.wp_distance,
|
||||
(int)pkt.wp_bearing,
|
||||
(int)pkt.lat_error,
|
||||
(int)pkt.lon_error,
|
||||
@ -859,22 +859,30 @@ static void Log_Read_Mode()
|
||||
{
|
||||
struct log_Mode pkt;
|
||||
DataFlash.ReadPacket(&pkt, sizeof(pkt));
|
||||
cliSerial->printf_P(PSTR("MOD:"));
|
||||
cliSerial->printf_P(PSTR("MOD,"));
|
||||
print_flight_mode(pkt.mode);
|
||||
cliSerial->printf_P(PSTR(", %d\n"),(int)pkt.throttle_cruise);
|
||||
}
|
||||
|
||||
struct log_Startup {
|
||||
LOG_PACKET_HEADER;
|
||||
};
|
||||
|
||||
// Write Startup packet. Total length : 4 bytes
|
||||
static void Log_Write_Startup()
|
||||
{
|
||||
DataFlash.WriteByte(HEAD_BYTE1);
|
||||
DataFlash.WriteByte(HEAD_BYTE2);
|
||||
DataFlash.WriteByte(LOG_STARTUP_MSG);
|
||||
struct log_Startup pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_STARTUP_MSG)
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
// Read a startup packet
|
||||
static void Log_Read_Startup()
|
||||
{
|
||||
struct log_Startup pkt;
|
||||
DataFlash.ReadPacket(&pkt, sizeof(pkt));
|
||||
cliSerial->printf_P(PSTR("START UP\n"));
|
||||
}
|
||||
|
||||
@ -900,7 +908,7 @@ static void Log_Read_Event()
|
||||
{
|
||||
struct log_Event pkt;
|
||||
DataFlash.ReadPacket(&pkt, sizeof(pkt));
|
||||
cliSerial->printf_P(PSTR("EV: %u\n"), (unsigned)pkt.id);
|
||||
cliSerial->printf_P(PSTR("EV, %u\n"), (unsigned)pkt.id);
|
||||
}
|
||||
|
||||
struct log_Data_Int16t {
|
||||
@ -927,7 +935,7 @@ static void Log_Read_Int16t()
|
||||
{
|
||||
struct log_Data_Int16t pkt;
|
||||
DataFlash.ReadPacket(&pkt, sizeof(pkt));
|
||||
cliSerial->printf_P(PSTR("DATA: %u, %d\n"), (unsigned)pkt.id, (int)pkt.data_value);
|
||||
cliSerial->printf_P(PSTR("DATA, %u, %d\n"), (unsigned)pkt.id, (int)pkt.data_value);
|
||||
}
|
||||
|
||||
struct log_Data_UInt16t {
|
||||
@ -954,7 +962,7 @@ static void Log_Read_UInt16t()
|
||||
{
|
||||
struct log_Data_UInt16t pkt;
|
||||
DataFlash.ReadPacket(&pkt, sizeof(pkt));
|
||||
cliSerial->printf_P(PSTR("DATA: %u, %u\n"), (unsigned)pkt.id, (unsigned)pkt.data_value);
|
||||
cliSerial->printf_P(PSTR("DATA, %u, %u\n"), (unsigned)pkt.id, (unsigned)pkt.data_value);
|
||||
}
|
||||
|
||||
struct log_Data_Int32t {
|
||||
@ -981,7 +989,7 @@ static void Log_Read_Int32t()
|
||||
{
|
||||
struct log_Data_Int32t pkt;
|
||||
DataFlash.ReadPacket(&pkt, sizeof(pkt));
|
||||
cliSerial->printf_P(PSTR("DATA: %u, %ld\n"), (unsigned)pkt.id, (long)pkt.data_value);
|
||||
cliSerial->printf_P(PSTR("DATA, %u, %ld\n"), (unsigned)pkt.id, (long)pkt.data_value);
|
||||
}
|
||||
|
||||
struct log_Data_UInt32t {
|
||||
@ -1008,7 +1016,7 @@ static void Log_Read_UInt32t()
|
||||
{
|
||||
struct log_Data_UInt32t pkt;
|
||||
DataFlash.ReadPacket(&pkt, sizeof(pkt));
|
||||
cliSerial->printf_P(PSTR("DATA: %u, %lu\n"), (unsigned)pkt.id, (unsigned long)pkt.data_value);
|
||||
cliSerial->printf_P(PSTR("DATA, %u, %lu\n"), (unsigned)pkt.id, (unsigned long)pkt.data_value);
|
||||
}
|
||||
|
||||
struct log_Data_Float {
|
||||
@ -1035,7 +1043,7 @@ static void Log_Read_Float()
|
||||
{
|
||||
struct log_Data_Float pkt;
|
||||
DataFlash.ReadPacket(&pkt, sizeof(pkt));
|
||||
cliSerial->printf_P(PSTR("DATA: %u, %1.6f\n"), (unsigned)pkt.id, (float)pkt.data_value);
|
||||
cliSerial->printf_P(PSTR("DATA, %u, %1.6f\n"), (unsigned)pkt.id, (float)pkt.data_value);
|
||||
}
|
||||
|
||||
struct log_PID {
|
||||
@ -1354,60 +1362,31 @@ static void log_callback(uint8_t msgid)
|
||||
|
||||
#else // LOGGING_ENABLED
|
||||
|
||||
static void Log_Write_Startup() {
|
||||
}
|
||||
static void Log_Read_Startup() {
|
||||
}
|
||||
static void Log_Read(int16_t start_page, int16_t end_page) {
|
||||
}
|
||||
static void Log_Write_Cmd(uint8_t num, struct Location *wp) {
|
||||
}
|
||||
static void Log_Write_Mode(uint8_t mode) {
|
||||
}
|
||||
static void Log_Write_IMU() {
|
||||
}
|
||||
void print_latlon(AP_HAL::BetterStream *s, int32_t lat_or_lon) {
|
||||
}
|
||||
static void Log_Write_GPS() {
|
||||
}
|
||||
static void Log_Write_Current() {
|
||||
}
|
||||
static void Log_Write_Iterm() {
|
||||
}
|
||||
static void Log_Write_Attitude() {
|
||||
}
|
||||
static void Log_Write_INAV() {
|
||||
}
|
||||
static void Log_Write_Data(uint8_t id, int16_t value){
|
||||
}
|
||||
static void Log_Write_Data(uint8_t id, uint16_t value){
|
||||
}
|
||||
static void Log_Write_Data(uint8_t id, int32_t value){
|
||||
}
|
||||
static void Log_Write_Data(uint8_t id, uint32_t value){
|
||||
}
|
||||
static void Log_Write_Data(uint8_t id, float value){
|
||||
}
|
||||
static void Log_Write_Event(uint8_t id){
|
||||
}
|
||||
static void Log_Write_Optflow() {
|
||||
}
|
||||
static void Log_Write_Nav_Tuning() {
|
||||
}
|
||||
static void Log_Write_Control_Tuning() {
|
||||
}
|
||||
static void Log_Write_Motors() {
|
||||
}
|
||||
static void Log_Write_Performance() {
|
||||
}
|
||||
static void Log_Write_PID(uint8_t pid_id, int32_t error, int32_t p, int32_t i, int32_t d, int32_t output, float gain) {
|
||||
}
|
||||
static void Log_Write_DMP() {
|
||||
}
|
||||
static void Log_Write_Camera() {
|
||||
}
|
||||
static void Log_Write_Error(uint8_t sub_system, uint8_t error_code) {
|
||||
}
|
||||
void print_latlon(AP_HAL::BetterStream *s, int32_t lat_or_lon) {}
|
||||
static void Log_Write_Startup() {}
|
||||
static void Log_Write_Cmd(uint8_t num, struct Location *wp) {}
|
||||
static void Log_Write_Mode(uint8_t mode) {}
|
||||
static void Log_Write_IMU() {}
|
||||
static void Log_Write_GPS() {}
|
||||
static void Log_Write_Current() {}
|
||||
static void Log_Write_Iterm() {}
|
||||
static void Log_Write_Attitude() {}
|
||||
static void Log_Write_INAV() {}
|
||||
static void Log_Write_Data(uint8_t id, int16_t value){}
|
||||
static void Log_Write_Data(uint8_t id, uint16_t value){}
|
||||
static void Log_Write_Data(uint8_t id, int32_t value){}
|
||||
static void Log_Write_Data(uint8_t id, uint32_t value){}
|
||||
static void Log_Write_Data(uint8_t id, float value){}
|
||||
static void Log_Write_Event(uint8_t id){}
|
||||
static void Log_Write_Optflow() {}
|
||||
static void Log_Write_Nav_Tuning() {}
|
||||
static void Log_Write_Control_Tuning() {}
|
||||
static void Log_Write_Motors() {}
|
||||
static void Log_Write_Performance() {}
|
||||
static void Log_Write_PID(uint8_t pid_id, int32_t error, int32_t p, int32_t i, int32_t d, int32_t output, float gain) {}
|
||||
static void Log_Write_DMP() {}
|
||||
static void Log_Write_Camera() {}
|
||||
static void Log_Write_Error(uint8_t sub_system, uint8_t error_code) {}
|
||||
static int8_t process_logs(uint8_t argc, const Menu::arg *argv) {
|
||||
return 0;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user