Copter: make copter code compatible with the new logging system

not fully converted yet
This commit is contained in:
Andrew Tridgell 2013-04-19 17:54:31 +10:00
parent c8af70a18d
commit 67484a2ea1
5 changed files with 12 additions and 79 deletions

View File

@ -1196,7 +1196,7 @@ static void fifty_hz_loop()
}
if (g.log_bitmask & MASK_LOG_IMU && motors.armed())
Log_Write_IMU();
DataFlash.Log_Write_IMU(&ins);
#endif
}
@ -1358,7 +1358,7 @@ static void update_GPS(void)
// log location if we have at least a 2D fix
if (g.log_bitmask & MASK_LOG_GPS && motors.armed()) {
Log_Write_GPS();
DataFlash.Log_Write_GPS(g_gps, current_loc.alt);
}
// for performance monitoring

View File

@ -1490,7 +1490,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);
@ -2159,7 +2159,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,

View File

@ -180,35 +180,6 @@ void print_latlon(AP_HAL::BetterStream *s, int32_t lat_or_lon)
s->printf_P(PSTR("%ld.%07ld"),(long)dec_portion,(long)frac_portion);
}
struct log_GPS {
LOG_PACKET_HEADER;
uint32_t gps_time;
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 : 31 bytes
static void Log_Write_GPS()
{
struct log_GPS pkt = {
LOG_PACKET_HEADER_INIT(LOG_GPS_MSG),
gps_time : g_gps->time,
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()
{
@ -230,23 +201,6 @@ static void Log_Read_GPS()
(long)pkt.ground_course);
}
struct log_IMU {
LOG_PACKET_HEADER;
Vector3f gyro;
Vector3f accel;
};
// Write an imu accel/gyro packet. Total length : 27 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()
{
@ -255,12 +209,12 @@ static void Log_Read_IMU()
// 1 2 3 4 5 6
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 {

View File

@ -262,12 +262,10 @@ enum gcs_severity {
#define TYPE_AIRSTART_MSG 0x00
#define TYPE_GROUNDSTART_MSG 0x01
#define LOG_ATTITUDE_MSG 0x01
#define LOG_GPS_MSG 0x02
#define LOG_MODE_MSG 0x03
#define LOG_CONTROL_TUNING_MSG 0x04
#define LOG_NAV_TUNING_MSG 0x05
#define LOG_PERFORMANCE_MSG 0x06
#define LOG_IMU_MSG 0x07
#define LOG_CMD_MSG 0x08
#define LOG_CURRENT_MSG 0x09
#define LOG_STARTUP_MSG 0x0A

View File

@ -96,26 +96,7 @@ 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;
}
@ -137,7 +118,7 @@ setup_show(uint8_t argc, const Menu::arg *argv)
report_gyro();
#endif
AP_Param::show_all();
AP_Param::show_all(cliSerial);
return(0);
}