Browse Source

Plane: make the plane code compatible with the new logging system

not actually converted yet
mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
c8af70a18d
  1. 4
      ArduPlane/ArduPlane.pde
  2. 4
      ArduPlane/GCS_Mavlink.pde
  3. 67
      ArduPlane/Log.pde
  4. 6
      ArduPlane/defines.h
  5. 95
      ArduPlane/setup.pde

4
ArduPlane/ArduPlane.pde

@ -759,7 +759,7 @@ static void fast_loop() @@ -759,7 +759,7 @@ static void fast_loop()
Log_Write_Attitude();
if (g.log_bitmask & MASK_LOG_IMU)
Log_Write_IMU();
DataFlash.Log_Write_IMU(&ins);
// inertial navigation
// ------------------
@ -877,7 +877,7 @@ static void medium_loop() @@ -877,7 +877,7 @@ static void medium_loop()
Log_Write_Nav_Tuning();
if (g.log_bitmask & MASK_LOG_GPS)
Log_Write_GPS();
DataFlash.Log_Write_GPS(g_gps, current_loc.alt);
break;
// This case controls the slow loop

4
ArduPlane/GCS_Mavlink.pde

@ -1408,7 +1408,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) @@ -1408,7 +1408,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
gcs_send_text_fmt(PSTR("Unknown parameter index %d"), packet.param_index);
break;
}
vp->copy_name_token(&token, param_name, AP_MAX_NAME_SIZE, true);
vp->copy_name_token(token, param_name, AP_MAX_NAME_SIZE, true);
param_name[AP_MAX_NAME_SIZE] = 0;
} else {
strncpy(param_name, packet.param_id, AP_MAX_NAME_SIZE);
@ -2037,7 +2037,7 @@ GCS_MAVLINK::queued_param_send() @@ -2037,7 +2037,7 @@ GCS_MAVLINK::queued_param_send()
value = vp->cast_to_float(_queued_parameter_type);
char param_name[AP_MAX_NAME_SIZE];
vp->copy_name_token(&_queued_parameter_token, param_name, sizeof(param_name), true);
vp->copy_name_token(_queued_parameter_token, param_name, sizeof(param_name), true);
mavlink_msg_param_value_send(
chan,

67
ArduPlane/Log.pde

@ -513,37 +513,6 @@ static void Log_Read_Mode() @@ -513,37 +513,6 @@ static void Log_Read_Mode()
print_flight_mode(pkt.mode);
}
struct log_GPS {
LOG_PACKET_HEADER;
uint32_t gps_time;
uint8_t status;
uint8_t num_sats;
int32_t latitude;
int32_t longitude;
int32_t rel_altitude;
int32_t altitude;
uint32_t ground_speed;
int32_t ground_course;
};
// Write an GPS packet. Total length : 30 bytes
static void Log_Write_GPS(void)
{
struct log_GPS pkt = {
LOG_PACKET_HEADER_INIT(LOG_GPS_MSG),
gps_time : g_gps->time,
status : g_gps->status(),
num_sats : g_gps->num_sats,
latitude : g_gps->latitude,
longitude : g_gps->longitude,
rel_altitude : current_loc.alt,
altitude : g_gps->altitude,
ground_speed : g_gps->ground_speed,
ground_course : g_gps->ground_course
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
// Read a GPS packet
static void Log_Read_GPS()
{
@ -562,35 +531,18 @@ static void Log_Read_GPS() @@ -562,35 +531,18 @@ static void Log_Read_GPS()
(long)pkt.ground_course);
}
struct log_IMU {
LOG_PACKET_HEADER;
Vector3f gyro;
Vector3f accel;
};
// Write an raw accel/gyro data packet. Total length : 28 bytes
static void Log_Write_IMU()
{
struct log_IMU pkt = {
LOG_PACKET_HEADER_INIT(LOG_IMU_MSG),
gyro : ins.get_gyro(),
accel : ins.get_accel()
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
// Read a raw accel/gyro packet
static void Log_Read_IMU()
{
struct log_IMU pkt;
DataFlash.ReadPacket(&pkt, sizeof(pkt));
cliSerial->printf_P(PSTR("IMU, %4.4f, %4.4f, %4.4f, %4.4f, %4.4f, %4.4f\n"),
pkt.gyro.x,
pkt.gyro.y,
pkt.gyro.z,
pkt.accel.x,
pkt.accel.y,
pkt.accel.z);
pkt.gyro_x,
pkt.gyro_y,
pkt.gyro_z,
pkt.accel_x,
pkt.accel_y,
pkt.accel_z);
}
struct log_Current {
@ -634,10 +586,6 @@ static void Log_Read(uint16_t log_num, int16_t start_page, int16_t end_page) @@ -634,10 +586,6 @@ static void Log_Read(uint16_t log_num, int16_t start_page, int16_t end_page)
cliSerial->println_P(PSTR(HAL_BOARD_NAME));
#if CLI_ENABLED == ENABLED
setup_show(0, NULL);
#endif
DataFlash.log_read_process(log_num, start_page, end_page, log_callback);
}
@ -685,16 +633,13 @@ static void log_callback(uint8_t msgid) @@ -685,16 +633,13 @@ static void log_callback(uint8_t msgid)
#else // LOGGING_ENABLED
// dummy functions
static void Log_Write_Mode(uint8_t mode) {}
static void Log_Write_Startup(uint8_t type) {}
static void Log_Write_Cmd(uint8_t num, const struct Location *wp) {}
static void Log_Write_Current() {}
static void Log_Write_Nav_Tuning() {}
static void Log_Write_GPS() {}
static void Log_Write_Performance() {}
static void Log_Write_Attitude() {}
static void Log_Write_Control_Tuning() {}
static void Log_Write_IMU() {}
static void Log_Write_Camera() {}
static int8_t process_logs(uint8_t argc, const Menu::arg *argv) {

6
ArduPlane/defines.h

@ -158,19 +158,17 @@ enum gcs_severity { @@ -158,19 +158,17 @@ enum gcs_severity {
// mark unused ones as 'deprecated', but leave them in
enum log_messages {
LOG_INDEX_MSG,
LOG_ATTITUDE_MSG,
LOG_GPS_MSG,
LOG_MODE_MSG,
LOG_CONTROL_TUNING_MSG,
LOG_NAV_TUNING_MSG,
LOG_PERFORMANCE_MSG,
LOG_IMU_MSG,
LOG_CMD_MSG,
LOG_CURRENT_MSG,
LOG_STARTUP_MSG,
TYPE_AIRSTART_MSG,
TYPE_GROUNDSTART_MSG,
LOG_CAMERA_MSG,
LOG_ATTITUDE_MSG,
LOG_MODE_MSG,
MAX_NUM_LOGS
};

95
ArduPlane/setup.pde

@ -80,45 +80,12 @@ setup_show(uint8_t argc, const Menu::arg *argv) @@ -80,45 +80,12 @@ setup_show(uint8_t argc, const Menu::arg *argv)
cliSerial->printf_P(PSTR("Parameter not found: '%s'\n"), argv[1]);
return 0;
}
//Print differently for different types, and include parameter type in output.
switch (type) {
case AP_PARAM_INT8:
cliSerial->printf_P(PSTR("INT8 %s: %d\n"), argv[1].str, (int)((AP_Int8 *)param)->get());
break;
case AP_PARAM_INT16:
cliSerial->printf_P(PSTR("INT16 %s: %d\n"), argv[1].str, (int)((AP_Int16 *)param)->get());
break;
case AP_PARAM_INT32:
cliSerial->printf_P(PSTR("INT32 %s: %ld\n"), argv[1].str, (long)((AP_Int32 *)param)->get());
break;
case AP_PARAM_FLOAT:
cliSerial->printf_P(PSTR("FLOAT %s: %f\n"), argv[1].str, ((AP_Float *)param)->get());
break;
default:
cliSerial->printf_P(PSTR("Unhandled parameter type for %s: %d.\n"), argv[1].str, type);
break;
}
AP_Param::show(param, argv[1].str, type, cliSerial);
return 0;
}
#endif
// clear the area
print_blanks(8);
report_radio();
report_batt_monitor();
report_gains();
report_throttle();
report_flight_modes();
report_ins();
report_compass();
cliSerial->printf_P(PSTR("Raw Values\n"));
print_divider();
AP_Param::show_all();
AP_Param::show_all(cliSerial);
return(0);
}
@ -511,54 +478,6 @@ static void report_radio() @@ -511,54 +478,6 @@ static void report_radio()
print_blanks(2);
}
static void report_gains()
{
//print_blanks(2);
cliSerial->printf_P(PSTR("Gains\n"));
print_divider();
#if APM_CONTROL == DISABLED
cliSerial->printf_P(PSTR("servo roll:\n"));
print_PID(&g.pidServoRoll);
cliSerial->printf_P(PSTR("servo pitch:\n"));
print_PID(&g.pidServoPitch);
cliSerial->printf_P(PSTR("servo rudder:\n"));
print_PID(&g.pidServoRudder);
#endif
cliSerial->printf_P(PSTR("nav pitch airspeed:\n"));
print_PID(&g.pidNavPitchAirspeed);
cliSerial->printf_P(PSTR("energry throttle:\n"));
print_PID(&g.pidTeThrottle);
cliSerial->printf_P(PSTR("nav pitch alt:\n"));
print_PID(&g.pidNavPitchAltitude);
print_blanks(2);
}
static void report_throttle()
{
//print_blanks(2);
cliSerial->printf_P(PSTR("Throttle\n"));
print_divider();
cliSerial->printf_P(PSTR("min: %d\n"
"max: %d\n"
"cruise: %d\n"
"failsafe_enabled: %d\n"
"failsafe_value: %d\n"),
(int)g.throttle_min,
(int)g.throttle_max,
(int)g.throttle_cruise,
(int)g.throttle_fs_enabled,
(int)g.throttle_fs_value);
print_blanks(2);
}
static void report_ins()
{
//print_blanks(2);
@ -624,16 +543,6 @@ static void report_flight_modes() @@ -624,16 +543,6 @@ static void report_flight_modes()
// CLI utilities
/***************************************************************************/
static void
print_PID(PID * pid)
{
cliSerial->printf_P(PSTR("P: %4.3f, I:%4.3f, D:%4.3f, IMAX:%ld\n"),
pid->kP(),
pid->kI(),
pid->kD(),
(long)pid->imax());
}
static void
print_radio_values()
{

Loading…
Cancel
Save