Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • opensource/ardupilot
  • opensource/baitboat
2 results
Show changes
Commits on Source (360)
Showing
with 808 additions and 721 deletions
*~
*.bin
*.cproject
*.d
*.dll
*.exe
*.lst
*.o
*.obj
*.project
*.px4
*.pyc
*.tlog
......
<?xml version="1.0" encoding="UTF-8"?>
<projectDescription>
<name>ArduPilotMega-Source@ardupilotone</name>
<comment></comment>
<projects>
</projects>
<buildSpec>
</buildSpec>
<natures>
</natures>
</projectDescription>
......@@ -252,7 +252,7 @@ AP_InertialSensor_Oilpan ins( &adc );
#error Unrecognised CONFIG_INS_TYPE setting.
#endif // CONFIG_INS_TYPE
AP_AHRS_DCM ahrs(&ins, g_gps);
AP_AHRS_DCM ahrs(ins, g_gps);
static AP_L1_Control L1_controller(ahrs);
......@@ -523,52 +523,56 @@ static float G_Dt = 0.02;
// Timer used to accrue data and trigger recording of the performanc monitoring log message
static int32_t perf_mon_timer;
// The maximum main loop execution time recorded in the current performance monitoring interval
static int16_t G_Dt_max = 0;
static uint32_t G_Dt_max;
// The number of gps fixes recorded in the current performance monitoring interval
static uint8_t gps_fix_count = 0;
// A variable used by developers to track performanc metrics.
// Currently used to record the number of GCS heartbeat messages received
static int16_t pmTest1 = 0;
////////////////////////////////////////////////////////////////////////////////
// System Timers
////////////////////////////////////////////////////////////////////////////////
// Time in miliseconds of start of main control loop. Milliseconds
static uint32_t fast_loopTimer;
// Time Stamp when fast loop was complete. Milliseconds
static uint32_t fast_loopTimeStamp;
// Time in microseconds of start of main control loop.
static uint32_t fast_loopTimer_us;
// Number of milliseconds used in last main loop cycle
static uint8_t delta_ms_fast_loop;
static uint32_t delta_us_fast_loop;
// Counter of main loop executions. Used for performance monitoring and failsafe processing
static uint16_t mainLoop_count;
// set if we are driving backwards
static bool in_reverse;
////////////////////////////////////////////////////////////////////////////////
// Top-level logic
////////////////////////////////////////////////////////////////////////////////
/*
scheduler table - all regular tasks apart from the fast_loop()
should be listed here, along with how often they should be called
(in 20ms units) and the maximum time they are expected to take (in
microseconds)
scheduler table - all regular tasks should be listed here, along
with how often they should be called (in 20ms units) and the maximum
time they are expected to take (in microseconds)
*/
static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
{ read_radio, 1, 1000 },
{ ahrs_update, 1, 6400 },
{ read_sonars, 1, 2000 },
{ update_current_mode, 1, 1000 },
{ set_servos, 1, 1000 },
{ update_GPS, 5, 2500 },
{ navigate, 5, 1600 },
{ update_compass, 5, 2000 },
{ update_commands, 5, 1000 },
{ update_logging, 5, 1000 },
{ gcs_retry_deferred, 1, 1000 },
{ gcs_update, 1, 1700 },
{ gcs_data_stream_send, 1, 3000 },
{ read_control_switch, 15, 1000 },
{ read_trim_switch, 5, 1000 },
{ read_battery, 5, 1000 },
{ read_receiver_rssi, 5, 1000 },
{ read_trim_switch, 5, 1000 },
{ read_control_switch, 15, 1000 },
{ update_events, 15, 1000 },
{ check_usb_mux, 15, 1000 },
{ mount_update, 1, 500 },
{ gcs_failsafe_check, 5, 500 },
{ mount_update, 1, 600 },
{ gcs_failsafe_check, 5, 600 },
{ compass_accumulate, 1, 900 },
{ update_notify, 1, 100 },
{ update_notify, 1, 300 },
{ one_second_loop, 50, 3000 }
};
......@@ -610,66 +614,44 @@ void loop()
if (!ins.wait_for_sample(1000)) {
return;
}
uint32_t timer = millis();
uint32_t timer = hal.scheduler->micros();
delta_ms_fast_loop = timer - fast_loopTimer;
G_Dt = (float)delta_ms_fast_loop / 1000.f;
fast_loopTimer = timer;
delta_us_fast_loop = timer - fast_loopTimer_us;
G_Dt = delta_us_fast_loop * 1.0e-6f;
fast_loopTimer_us = timer;
mainLoop_count++;
if (delta_us_fast_loop > G_Dt_max)
G_Dt_max = delta_us_fast_loop;
// Execute the fast loop
// ---------------------
fast_loop();
mainLoop_count++;
// tell the scheduler one tick has passed
scheduler.tick();
fast_loopTimeStamp = millis();
scheduler.run(19000U);
scheduler.run(19500U);
}
// Main loop 50Hz
static void fast_loop()
// update AHRS system
static void ahrs_update()
{
// This is the fast loop - we want it to execute at 50Hz if possible
// -----------------------------------------------------------------
if (delta_ms_fast_loop > G_Dt_max)
G_Dt_max = delta_ms_fast_loop;
// Read radio
// ----------
read_radio();
// try to send any deferred messages if the serial port now has
// some space available
gcs_send_message(MSG_RETRY_DEFERRED);
#if HIL_MODE != HIL_MODE_DISABLED
// update hil before dcm update
gcs_update();
#endif
#if HIL_MODE != HIL_MODE_DISABLED
// update hil before AHRS update
gcs_update();
#endif
ahrs.update();
// when in reverse we need to tell AHRS not to assume we are a
// 'fly forward' vehicle, otherwise it will see a large
// discrepancy between the mag and the GPS heading and will try to
// correct for it, leading to a large yaw error
ahrs.set_fly_forward(!in_reverse);
read_sonars();
ahrs.update();
if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST)
Log_Write_Attitude();
if (g.log_bitmask & MASK_LOG_IMU)
DataFlash.Log_Write_IMU(&ins);
// custom code/exceptions for flight modes
// ---------------------------------------
update_current_mode();
// write out the servo PWM values
// ------------------------------
set_servos();
gcs_update();
gcs_data_stream_send();
DataFlash.Log_Write_IMU(ins);
}
/*
......@@ -787,9 +769,13 @@ static void one_second_loop(void)
counter++;
// write perf data every 20s
if (counter == 20) {
if (counter % 10 == 0) {
if (scheduler.debug() != 0) {
hal.console->printf_P(PSTR("G_Dt_max=%lu\n"), (unsigned long)G_Dt_max);
}
if (g.log_bitmask & MASK_LOG_PM)
Log_Write_Performance();
G_Dt_max = 0;
resetPerfData();
}
......@@ -832,6 +818,10 @@ static void update_GPS(void)
} else {
init_home();
// set system clock for log timestamps
hal.util->set_system_clock(g_gps->time_epoch_usec());
if (g.compass_enabled) {
// Set compass declination automatically
compass.set_initial_location(g_gps->latitude, g_gps->longitude);
......@@ -879,7 +869,12 @@ static void update_current_mode(void)
// and throttle gives speed in proportion to cruise speed, up
// to 50% throttle, then uses nudging above that.
float target_speed = channel_throttle->pwm_to_angle() * 0.01 * 2 * g.speed_cruise;
target_speed = constrain_float(target_speed, 0, g.speed_cruise);
in_reverse = (target_speed < 0);
if (in_reverse) {
target_speed = constrain_float(target_speed, -g.speed_cruise, 0);
} else {
target_speed = constrain_float(target_speed, 0, g.speed_cruise);
}
calc_throttle(target_speed);
break;
}
......@@ -894,6 +889,10 @@ static void update_current_mode(void)
*/
channel_throttle->servo_out = channel_throttle->control_in;
channel_steer->servo_out = channel_steer->pwm_to_angle();
// mark us as in_reverse when using a negative throttle to
// stop AHRS getting off
in_reverse = (channel_throttle->servo_out < 0);
break;
case HOLD:
......
......@@ -9,6 +9,9 @@ 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
static bool gcs_out_of_time;
// check if a message will fit in the payload space available
#define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_## id ##_LEN) return false
......@@ -158,6 +161,9 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
if (g_gps != NULL && g_gps->status() > GPS::NO_GPS) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
}
if (!ins.healthy()) {
control_sensors_health &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
}
int16_t battery_current = -1;
int8_t battery_remaining = -1;
......@@ -246,6 +252,14 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan)
g_gps->num_sats);
}
static void NOINLINE send_system_time(mavlink_channel_t chan)
{
mavlink_msg_system_time_send(
chan,
g_gps->time_epoch_usec(),
hal.scheduler->millis());
}
#if HIL_MODE != HIL_MODE_DISABLED
static void NOINLINE send_servo_out(mavlink_channel_t chan)
......@@ -471,6 +485,14 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
return false;
}
// if we don't have at least 1ms remaining before the main loop
// wants to fire then don't send a mavlink message. We want to
// prioritise the main flight control loop over communications
if (!in_mavlink_delay && scheduler.time_available_usec() < 1200) {
gcs_out_of_time = true;
return false;
}
switch (id) {
case MSG_HEARTBEAT:
CHECK_PAYLOAD_SIZE(HEARTBEAT);
......@@ -509,6 +531,11 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
send_gps_raw(chan);
break;
case MSG_SYSTEM_TIME:
CHECK_PAYLOAD_SIZE(SYSTEM_TIME);
send_system_time(chan);
break;
case MSG_SERVO_OUT:
#if HIL_MODE != HIL_MODE_DISABLED
CHECK_PAYLOAD_SIZE(RC_CHANNELS_SCALED);
......@@ -756,8 +783,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] PROGMEM = {
// @Range: 0 10
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK, streamRates[8], 5),
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK, streamRates[8], 10),
AP_GROUPEND
};
......@@ -858,7 +884,8 @@ bool GCS_MAVLINK::stream_trigger(enum streams stream_num)
// send at a much lower rate while handling waypoints and
// parameter sends
if (waypoint_receiving || _queued_parameter != NULL) {
if ((stream_num != STREAM_PARAMS) &&
(waypoint_receiving || _queued_parameter != NULL)) {
rate *= 0.25;
}
......@@ -883,18 +910,19 @@ bool GCS_MAVLINK::stream_trigger(enum streams stream_num)
void
GCS_MAVLINK::data_stream_send(void)
{
gcs_out_of_time = false;
if (_queued_parameter != NULL) {
if (streamRates[STREAM_PARAMS].get() <= 0) {
streamRates[STREAM_PARAMS].set(5);
}
if (streamRates[STREAM_PARAMS].get() > 5) {
streamRates[STREAM_PARAMS].set(5);
streamRates[STREAM_PARAMS].set(10);
}
if (stream_trigger(STREAM_PARAMS)) {
send_message(MSG_NEXT_PARAM);
}
}
if (gcs_out_of_time) return;
if (in_mavlink_delay) {
#if HIL_MODE != HIL_MODE_DISABLED
// in HIL we need to keep sending servo values to ensure
......@@ -911,11 +939,15 @@ GCS_MAVLINK::data_stream_send(void)
return;
}
if (gcs_out_of_time) return;
if (stream_trigger(STREAM_RAW_SENSORS)) {
send_message(MSG_RAW_IMU1);
send_message(MSG_RAW_IMU3);
}
if (gcs_out_of_time) return;
if (stream_trigger(STREAM_EXTENDED_STATUS)) {
send_message(MSG_EXTENDED_STATUS1);
send_message(MSG_EXTENDED_STATUS2);
......@@ -924,33 +956,46 @@ GCS_MAVLINK::data_stream_send(void)
send_message(MSG_NAV_CONTROLLER_OUTPUT);
}
if (gcs_out_of_time) return;
if (stream_trigger(STREAM_POSITION)) {
// sent with GPS read
send_message(MSG_LOCATION);
}
if (gcs_out_of_time) return;
if (stream_trigger(STREAM_RAW_CONTROLLER)) {
send_message(MSG_SERVO_OUT);
}
if (gcs_out_of_time) return;
if (stream_trigger(STREAM_RC_CHANNELS)) {
send_message(MSG_RADIO_OUT);
send_message(MSG_RADIO_IN);
}
if (gcs_out_of_time) return;
if (stream_trigger(STREAM_EXTRA1)) {
send_message(MSG_ATTITUDE);
send_message(MSG_SIMSTATE);
}
if (gcs_out_of_time) return;
if (stream_trigger(STREAM_EXTRA2)) {
send_message(MSG_VFR_HUD);
}
if (gcs_out_of_time) return;
if (stream_trigger(STREAM_EXTRA3)) {
send_message(MSG_AHRS);
send_message(MSG_HWSTATUS);
send_message(MSG_RANGEFINDER);
send_message(MSG_SYSTEM_TIME);
}
}
......@@ -1293,8 +1338,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
mavlink_msg_param_request_list_decode(msg, &packet);
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
// Start sending parameters - next call to ::update will kick the first one out
// mark the firmware version in the tlog
send_text_P(SEVERITY_LOW, PSTR(FIRMWARE_STRING));
// Start sending parameters - next call to ::update will kick the first one out
_queued_parameter = AP_Param::first(&_queued_parameter_token, &_queued_parameter_type);
_queued_parameter_index = 0;
_queued_parameter_count = _count_parameters();
......@@ -1713,7 +1760,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
if(msg->sysid != g.sysid_my_gcs) break;
last_heartbeat_ms = failsafe.rc_override_timer = millis();
failsafe_trigger(FAILSAFE_EVENT_GCS, false);
pmTest1++;
break;
}
......@@ -2007,3 +2053,11 @@ void gcs_send_text_fmt(const prog_char_t *fmt, ...)
}
}
/**
retry any deferred messages
*/
static void gcs_retry_deferred(void)
{
gcs_send_message(MSG_RETRY_DEFERRED);
}
......@@ -165,15 +165,14 @@ struct PACKED log_Performance {
LOG_PACKET_HEADER;
uint32_t loop_time;
uint16_t main_loop_count;
int16_t g_dt_max;
uint32_t g_dt_max;
uint8_t renorm_count;
uint8_t renorm_blowup;
uint8_t gps_fix_count;
int16_t gyro_drift_x;
int16_t gyro_drift_y;
int16_t gyro_drift_z;
int16_t pm_test;
uint8_t i2c_lockup_count;
uint16_t ins_error_count;
};
// Write a performance monitoring packet. Total length : 19 bytes
......@@ -186,12 +185,11 @@ static void Log_Write_Performance()
g_dt_max : G_Dt_max,
renorm_count : ahrs.renorm_range_count,
renorm_blowup : ahrs.renorm_blowup_count,
gps_fix_count : gps_fix_count,
gyro_drift_x : (int16_t)(ahrs.get_gyro_drift().x * 1000),
gyro_drift_y : (int16_t)(ahrs.get_gyro_drift().y * 1000),
gyro_drift_z : (int16_t)(ahrs.get_gyro_drift().z * 1000),
pm_test : pmTest1,
i2c_lockup_count: hal.i2c->lockup_count()
i2c_lockup_count: hal.i2c->lockup_count(),
ins_error_count : ins.error_count()
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
......@@ -228,6 +226,7 @@ static void Log_Write_Cmd(uint8_t num, const struct Location *wp)
struct PACKED log_Camera {
LOG_PACKET_HEADER;
uint32_t gps_time;
uint16_t gps_week;
int32_t latitude;
int32_t longitude;
int16_t roll;
......@@ -241,7 +240,8 @@ static void Log_Write_Camera()
#if CAMERA == ENABLED
struct log_Camera pkt = {
LOG_PACKET_HEADER_INIT(LOG_CAMERA_MSG),
gps_time : g_gps->time,
gps_time : g_gps->time_week_ms,
gps_week : g_gps->time_week,
latitude : current_loc.lat,
longitude : current_loc.lng,
roll : (int16_t)ahrs.roll_sensor,
......@@ -454,11 +454,11 @@ static const struct LogStructure log_structure[] PROGMEM = {
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),
"ATT", "ccC", "Roll,Pitch,Yaw" },
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
"PM", "IHhBBBhhhhB", "LTime,MLC,gDt,RNCnt,RNBl,GPScnt,GDx,GDy,GDz,PMT,I2CErr" },
"PM", "IHIBBhhhBH", "LTime,MLC,gDt,RNCnt,RNBl,GDx,GDy,GDz,I2CErr,INSErr" },
{ LOG_CMD_MSG, sizeof(log_Cmd),
"CMD", "BBBBBeLL", "CTot,CNum,CId,COpt,Prm1,Alt,Lat,Lng" },
{ LOG_CAMERA_MSG, sizeof(log_Camera),
"CAM", "ILLccC", "GPSTime,Lat,Lng,Roll,Pitch,Yaw" },
"CAM", "IHLLeccC", "GPSTime,GPSWeek,Lat,Lng,Alt,Roll,Pitch,Yaw" },
{ LOG_STARTUP_MSG, sizeof(log_Startup),
"STRT", "BB", "SType,CTot" },
{ LOG_CTUN_MSG, sizeof(log_Control_Tuning),
......@@ -479,7 +479,7 @@ static const struct LogStructure log_structure[] PROGMEM = {
// Read the DataFlash log memory : Packet Parser
static void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page)
{
cliSerial->printf_P(PSTR("\n" THISFIRMWARE
cliSerial->printf_P(PSTR("\n" FIRMWARE_STRING
"\nFree RAM: %u\n"),
(unsigned) memcheck_available_memory());
......@@ -496,6 +496,7 @@ static void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page)
static void start_logging()
{
DataFlash.StartNewLog(sizeof(log_structure)/sizeof(log_structure[0]), log_structure);
DataFlash.Log_Write_Message_P(PSTR(FIRMWARE_STRING));
}
#else // LOGGING_ENABLED
......
......@@ -75,13 +75,8 @@ static void calc_throttle(float target_speed)
return;
}
if (target_speed <= 0) {
// cope with zero requested speed
channel_throttle->servo_out = g.throttle_min.get();
return;
}
int throttle_target = g.throttle_cruise + throttle_nudge;
float throttle_base = (fabsf(target_speed) / g.speed_cruise) * g.throttle_cruise;
int throttle_target = throttle_base + throttle_nudge;
/*
reduce target speed in proportion to turning rate, up to the
......@@ -102,7 +97,7 @@ static void calc_throttle(float target_speed)
// reduce the target speed by the reduction factor
target_speed *= reduction;
groundspeed_error = target_speed - ground_speed;
groundspeed_error = fabsf(target_speed) - ground_speed;
throttle = throttle_target + (g.pidSpeedThrottle.get_pid(groundspeed_error * 100) / 100);
......@@ -110,7 +105,11 @@ static void calc_throttle(float target_speed)
// much faster response in turns
throttle *= reduction;
channel_throttle->servo_out = constrain_int16(throttle, g.throttle_min.get(), g.throttle_max.get());
if (in_reverse) {
channel_throttle->servo_out = constrain_int16(-throttle, -g.throttle_max, -g.throttle_min);
} else {
channel_throttle->servo_out = constrain_int16(throttle, g.throttle_min, g.throttle_max);
}
}
/*****************************************
......@@ -179,9 +178,15 @@ static void set_servos(void)
}
} else {
channel_steer->calc_pwm();
channel_throttle->servo_out = constrain_int16(channel_throttle->servo_out,
g.throttle_min.get(),
g.throttle_max.get());
if (in_reverse) {
channel_throttle->servo_out = constrain_int16(channel_throttle->servo_out,
-g.throttle_max,
-g.throttle_min);
} else {
channel_throttle->servo_out = constrain_int16(channel_throttle->servo_out,
g.throttle_min.get(),
g.throttle_max.get());
}
if ((failsafe.bits & FAILSAFE_EVENT_THROTTLE) && control_mode < AUTO) {
// suppress throttle if in failsafe
......
......@@ -366,3 +366,13 @@
#ifndef SONAR_ENABLED
# define SONAR_ENABLED DISABLED
#endif
/*
build a firmware version string.
GIT_VERSION comes from Makefile builds
*/
#ifndef GIT_VERSION
#define FIRMWARE_STRING THISFIRMWARE
#else
#define FIRMWARE_STRING THISFIRMWARE " (" GIT_VERSION ")"
#endif
......@@ -101,6 +101,7 @@ enum ap_message {
MSG_RAW_IMU1,
MSG_RAW_IMU3,
MSG_GPS_RAW,
MSG_SYSTEM_TIME,
MSG_SERVO_OUT,
MSG_NEXT_WAYPOINT,
MSG_NEXT_PARAM,
......
......@@ -94,7 +94,7 @@ static void init_ardupilot()
// standard gps running
hal.uartB->begin(115200, 256, 16);
cliSerial->printf_P(PSTR("\n\nInit " THISFIRMWARE
cliSerial->printf_P(PSTR("\n\nInit " FIRMWARE_STRING
"\n\nFree RAM: %u\n"),
memcheck_available_memory());
......@@ -252,6 +252,8 @@ static void set_mode(enum mode mode)
control_mode = mode;
throttle_last = 0;
throttle = 500;
in_reverse = false;
g.pidSpeedThrottle.reset_I();
if (control_mode != AUTO) {
auto_triggered = false;
......@@ -370,7 +372,6 @@ static void resetPerfData(void) {
ahrs.renorm_range_count = 0;
ahrs.renorm_blowup_count = 0;
gps_fix_count = 0;
pmTest1 = 0;
perf_mon_timer = millis();
}
......
......@@ -341,39 +341,32 @@ test_ins(uint8_t argc, const Menu::arg *argv)
uint8_t medium_loopCounter = 0;
while(1){
delay(20);
if (millis() - fast_loopTimer > 19) {
delta_ms_fast_loop = millis() - fast_loopTimer;
G_Dt = (float)delta_ms_fast_loop / 1000.f; // used by DCM integrator
fast_loopTimer = millis();
// INS
// ---
ahrs.update();
if(g.compass_enabled) {
medium_loopCounter++;
if(medium_loopCounter >= 5){
compass.read();
medium_loopCounter = 0;
}
}
// We are using the IMU
// ---------------------
Vector3f gyros = ins.get_gyro();
Vector3f accels = ins.get_accel();
cliSerial->printf_P(PSTR("r:%4d p:%4d y:%3d g=(%5.1f %5.1f %5.1f) a=(%5.1f %5.1f %5.1f)\n"),
ins.wait_for_sample(1000);
ahrs.update();
if(g.compass_enabled) {
medium_loopCounter++;
if(medium_loopCounter >= 5){
compass.read();
medium_loopCounter = 0;
}
}
// We are using the IMU
// ---------------------
Vector3f gyros = ins.get_gyro();
Vector3f accels = ins.get_accel();
cliSerial->printf_P(PSTR("r:%4d p:%4d y:%3d g=(%5.1f %5.1f %5.1f) a=(%5.1f %5.1f %5.1f)\n"),
(int)ahrs.roll_sensor / 100,
(int)ahrs.pitch_sensor / 100,
(uint16_t)ahrs.yaw_sensor / 100,
gyros.x, gyros.y, gyros.z,
accels.x, accels.y, accels.z);
}
if(cliSerial->available() > 0){
return (0);
}
}
}
if(cliSerial->available() > 0){
return (0);
}
}
......@@ -408,32 +401,25 @@ test_mag(uint8_t argc, const Menu::arg *argv)
uint8_t medium_loopCounter = 0;
while(1) {
delay(20);
if (millis() - fast_loopTimer > 19) {
delta_ms_fast_loop = millis() - fast_loopTimer;
G_Dt = (float)delta_ms_fast_loop / 1000.f; // used by DCM integrator
fast_loopTimer = millis();
// IMU
// ---
ahrs.update();
medium_loopCounter++;
if(medium_loopCounter >= 5){
if (compass.read()) {
// Calculate heading
Matrix3f m = ahrs.get_dcm_matrix();
heading = compass.calculate_heading(m);
compass.null_offsets();
}
medium_loopCounter = 0;
ins.wait_for_sample(1000);
ahrs.update();
medium_loopCounter++;
if(medium_loopCounter >= 5){
if (compass.read()) {
// Calculate heading
Matrix3f m = ahrs.get_dcm_matrix();
heading = compass.calculate_heading(m);
compass.null_offsets();
}
counter++;
if (counter>20) {
if (compass.healthy) {
Vector3f maggy = compass.get_offsets();
cliSerial->printf_P(PSTR("Heading: %ld, XYZ: %d, %d, %d,\tXYZoff: %6.2f, %6.2f, %6.2f\n"),
medium_loopCounter = 0;
}
counter++;
if (counter>20) {
if (compass.healthy) {
Vector3f maggy = compass.get_offsets();
cliSerial->printf_P(PSTR("Heading: %ld, XYZ: %d, %d, %d,\tXYZoff: %6.2f, %6.2f, %6.2f\n"),
(wrap_360_cd(ToDeg(heading) * 100)) /100,
(int)compass.mag_x,
(int)compass.mag_y,
......@@ -441,12 +427,11 @@ test_mag(uint8_t argc, const Menu::arg *argv)
maggy.x,
maggy.y,
maggy.z);
} else {
cliSerial->println_P(PSTR("compass not healthy"));
}
counter=0;
} else {
cliSerial->println_P(PSTR("compass not healthy"));
}
}
counter=0;
}
if (cliSerial->available() > 0) {
break;
}
......
......@@ -15,14 +15,24 @@
* OCTA_FRAME
* OCTA_QUAD_FRAME
* HELI_FRAME
* SINGLE_FRAME
*/
// uncomment the lines below to save on flash space if compiling for the APM using Arduino IDE
//#define OPTFLOW DISABLED // disable optical flow sensor to save 5K of flash space
// uncomment the lines below to save on flash space if compiling for the APM using Arduino IDE. Top items save the most flash space
//#define CLI_ENABLED DISABLED // disable the CLI (command-line-interface) to save 21K of flash space
//#define LOGGING_ENABLED DISABLED // disable dataflash logging to save 11K of flash space
//#define GPS_PROTOCOL GPS_PROTOCOL_UBLOX // hard code GPS to Ublox to save 8k of flash
//#define GPS_PROTOCOL GPS_PROTOCOL_MTK19 // hard cdoe GPS to Mediatek to save 10k of flash
//#define MOUNT DISABLED // disable the camera gimbal to save 8K of flash space
//#define CLI_ENABLED DISABLED // disable the CLI (command-line-interface) to save 21K of flash space
//#define AUTOTUNE DISABLED // disable the auto tune functionality to save 7k of flash
//#define OPTFLOW DISABLED // disable optical flow sensor to save 5K of flash space
//#define AC_FENCE DISABLED // disable fence to save 2k of flash
//#define CAMERA DISABLED // disable camera trigger to save 1k of flash
//#define COPTER_LEDS DISABLED // disable external navigation leds to save 1k of flash
//#define CONFIG_SONAR DISABLED // disable sonar to save 1k of flash
// features below are disabled by default
//#define SPRAYER ENABLED // enable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
// redefine size of throttle deadband in pwm (0 ~ 1000)
//#define THROTTLE_IN_DEADBAND 100
......
......@@ -25,7 +25,7 @@
// the loop port. Alternatively, use a telemetry/HIL shim like FGShim
// https://ardupilot-mega.googlecode.com/svn/Tools/trunk/FlightGear
//
// The buad rate is controlled by SERIAL3_BAUD in this mode.
// The buad rate is controlled by SERIAL1_BAUD in this mode.
#define HIL_PORT 3
......
......@@ -131,3 +131,10 @@ void set_pre_arm_check(bool b)
}
}
void set_pre_arm_rc_check(bool b)
{
if(ap.pre_arm_rc_check != b) {
ap.pre_arm_rc_check = b;
}
}
This diff is collapsed.
......@@ -7,6 +7,10 @@ static void get_pilot_desired_lean_angles(int16_t roll_in, int16_t pitch_in, int
static float _scaler = 1.0;
static int16_t _angle_max = 0;
// range check the input
roll_in = constrain_int16(roll_in, -ROLL_PITCH_INPUT_MAX, ROLL_PITCH_INPUT_MAX);
pitch_in = constrain_int16(pitch_in, -ROLL_PITCH_INPUT_MAX, ROLL_PITCH_INPUT_MAX);
// return immediately if no scaling required
if (g.angle_max == ROLL_PITCH_INPUT_MAX) {
roll_out = roll_in;
......@@ -36,7 +40,7 @@ get_stabilize_roll(int32_t target_angle)
// constrain the target rate
if (!ap.disable_stab_rate_limit) {
target_rate = constrain_int32(target_rate, -STABILIZE_RATE_LIMIT, STABILIZE_RATE_LIMIT);
target_rate = constrain_int32(target_rate, -g.angle_rate_max, g.angle_rate_max);
}
// set targets for rate controller
......@@ -54,7 +58,7 @@ get_stabilize_pitch(int32_t target_angle)
// constrain the target rate
if (!ap.disable_stab_rate_limit) {
target_rate = constrain_int32(target_rate, -STABILIZE_RATE_LIMIT, STABILIZE_RATE_LIMIT);
target_rate = constrain_int32(target_rate, -g.angle_rate_max, g.angle_rate_max);
}
// set targets for rate controller
......@@ -79,7 +83,7 @@ get_stabilize_yaw(int32_t target_angle)
// do not use rate controllers for helicotpers with external gyros
#if FRAME_CONFIG == HELI_FRAME
if(motors.ext_gyro_enabled) {
if(motors.tail_type() == AP_MOTORS_HELI_TAILTYPE_SERVO_EXTGYRO) {
g.rc_4.servo_out = constrain_int32(target_rate, -4500, 4500);
}
#endif
......@@ -99,15 +103,6 @@ get_stabilize_yaw(int32_t target_angle)
set_yaw_rate_target(target_rate, EARTH_FRAME);
}
static void
get_acro_yaw(int32_t target_rate)
{
target_rate = target_rate * g.acro_yaw_p;
// set targets for rate controller
set_yaw_rate_target(target_rate, BODY_FRAME);
}
// get_acro_level_rates - calculate earth frame rate corrections to pull the copter back to level while in ACRO mode
static void
get_acro_level_rates()
......@@ -192,9 +187,15 @@ get_roll_rate_stabilized_bf(int32_t stick_angle)
// don't let angle error grow too large
angle_error = constrain_float(angle_error, -MAX_ROLL_OVERSHOOT, MAX_ROLL_OVERSHOOT);
#if FRAME_CONFIG == HELI_FRAME
if (!motors.motor_runup_complete()) {
angle_error = 0;
}
#else
if (!motors.armed() || g.rc_3.servo_out == 0) {
angle_error = 0;
}
#endif // HELI_FRAME
}
// Pitch with rate input and stabilized in the body frame
......@@ -231,9 +232,15 @@ get_pitch_rate_stabilized_bf(int32_t stick_angle)
// don't let angle error grow too large
angle_error = constrain_float(angle_error, -MAX_PITCH_OVERSHOOT, MAX_PITCH_OVERSHOOT);
#if FRAME_CONFIG == HELI_FRAME
if (!motors.motor_runup_complete()) {
angle_error = 0;
}
#else
if (!motors.armed() || g.rc_3.servo_out == 0) {
angle_error = 0;
}
#endif // HELI_FRAME
}
// Yaw with rate input and stabilized in the body frame
......@@ -270,9 +277,15 @@ get_yaw_rate_stabilized_bf(int32_t stick_angle)
// don't let angle error grow too large
angle_error = constrain_float(angle_error, -MAX_YAW_OVERSHOOT, MAX_YAW_OVERSHOOT);
#if FRAME_CONFIG == HELI_FRAME
if (!motors.motor_runup_complete()) {
angle_error = 0;
}
#else
if (!motors.armed() || g.rc_3.servo_out == 0) {
angle_error = 0;
}
#endif // HELI_FRAME
}
// Roll with rate input and stabilized in the earth frame
......@@ -299,7 +312,7 @@ get_roll_rate_stabilized_ef(int32_t stick_angle)
}
#if FRAME_CONFIG == HELI_FRAME
if (!motors.motor_runup_complete) {
if (!motors.motor_runup_complete()) {
angle_error = 0;
}
#else
......@@ -340,7 +353,7 @@ get_pitch_rate_stabilized_ef(int32_t stick_angle)
}
#if FRAME_CONFIG == HELI_FRAME
if (!motors.motor_runup_complete) {
if (!motors.motor_runup_complete()) {
angle_error = 0;
}
#else
......@@ -378,7 +391,7 @@ get_yaw_rate_stabilized_ef(int32_t stick_angle)
angle_error = constrain_int32(angle_error, -MAX_YAW_OVERSHOOT, MAX_YAW_OVERSHOOT);
#if FRAME_CONFIG == HELI_FRAME
if (!motors.motor_runup_complete) {
if (!motors.motor_runup_complete()) {
angle_error = 0;
}
#else
......@@ -447,10 +460,15 @@ update_rate_contoller_targets()
void
run_rate_controllers()
{
#if FRAME_CONFIG == HELI_FRAME // helicopters only use rate controllers for yaw and only when not using an external gyro
if(!motors.ext_gyro_enabled) {
heli_integrated_swash_controller(roll_rate_target_bf, pitch_rate_target_bf);
#if FRAME_CONFIG == HELI_FRAME
// convert desired roll and pitch rate to roll and pitch swash angles
heli_integrated_swash_controller(roll_rate_target_bf, pitch_rate_target_bf);
// helicopters only use rate controllers for yaw and only when not using an external gyro
if(motors.tail_type() != AP_MOTORS_HELI_TAILTYPE_SERVO_EXTGYRO) {
g.rc_4.servo_out = get_heli_rate_yaw(yaw_rate_target_bf);
}else{
// do not use rate controllers for helicotpers with external gyros
g.rc_4.servo_out = constrain_int32(yaw_rate_target_bf, -4500, 4500);
}
#else
// call rate controllers
......@@ -465,143 +483,6 @@ run_rate_controllers()
}
}
#if FRAME_CONFIG == HELI_FRAME
// init_rate_controllers - set-up filters for rate controller inputs
void init_rate_controllers()
{
// initalise low pass filters on rate controller inputs
// 1st parameter is time_step, 2nd parameter is time_constant
// rate_roll_filter.set_cutoff_frequency(0.01f, 0.1f);
// rate_pitch_filter.set_cutoff_frequency(0.01f, 0.1f);
}
static void heli_integrated_swash_controller(int32_t target_roll_rate, int32_t target_pitch_rate)
{
int32_t roll_p, roll_i, roll_d, roll_ff; // used to capture pid values for logging
int32_t pitch_p, pitch_i, pitch_d, pitch_ff;
int32_t current_roll_rate, current_pitch_rate; // this iteration's rate
int32_t roll_rate_error, pitch_rate_error; // simply target_rate - current_rate
int32_t roll_output, pitch_output; // output from pid controller
static bool roll_pid_saturated, pitch_pid_saturated; // tracker from last loop if the PID was saturated
current_roll_rate = (omega.x * DEGX100); // get current roll rate
current_pitch_rate = (omega.y * DEGX100); // get current pitch rate
roll_rate_error = target_roll_rate - current_roll_rate;
pitch_rate_error = target_pitch_rate - current_pitch_rate;
roll_p = g.pid_rate_roll.get_p(roll_rate_error);
pitch_p = g.pid_rate_pitch.get_p(pitch_rate_error);
if (roll_pid_saturated){
roll_i = g.pid_rate_roll.get_integrator(); // Locked Integrator due to PID saturation on previous cycle
} else {
if (motors.flybar_mode == 1) { // Mechanical Flybars get regular integral for rate auto trim
if (target_roll_rate > -50 && target_roll_rate < 50){ // Frozen at high rates
roll_i = g.pid_rate_roll.get_i(roll_rate_error, G_Dt);
} else {
roll_i = g.pid_rate_roll.get_integrator();
}
} else {
roll_i = g.pid_rate_roll.get_leaky_i(roll_rate_error, G_Dt, RATE_INTEGRATOR_LEAK_RATE); // Flybarless Helis get huge I-terms. I-term controls much of the rate
}
}
if (pitch_pid_saturated){
pitch_i = g.pid_rate_pitch.get_integrator(); // Locked Integrator due to PID saturation on previous cycle
} else {
if (motors.flybar_mode == 1) { // Mechanical Flybars get regular integral for rate auto trim
if (target_pitch_rate > -50 && target_pitch_rate < 50){ // Frozen at high rates
pitch_i = g.pid_rate_pitch.get_i(pitch_rate_error, G_Dt);
} else {
pitch_i = g.pid_rate_pitch.get_integrator();
}
} else {
pitch_i = g.pid_rate_pitch.get_leaky_i(pitch_rate_error, G_Dt, RATE_INTEGRATOR_LEAK_RATE); // Flybarless Helis get huge I-terms. I-term controls much of the rate
}
}
roll_d = g.pid_rate_roll.get_d(target_roll_rate, G_Dt);
pitch_d = g.pid_rate_pitch.get_d(target_pitch_rate, G_Dt);
roll_ff = g.heli_roll_ff * target_roll_rate;
pitch_ff = g.heli_pitch_ff * target_pitch_rate;
// Joly, I think your PC and CC code goes here
roll_output = roll_p + roll_i + roll_d + roll_ff;
pitch_output = pitch_p + pitch_i + pitch_d + pitch_ff;
if (labs(roll_output) > 4500){
roll_output = constrain_int32(roll_output, -4500, 4500); // constrain output
roll_pid_saturated = true; // freeze integrator next cycle
} else {
roll_pid_saturated = false; // unfreeze integrator
}
if (labs(pitch_output) > 4500){
pitch_output = constrain_int32(pitch_output, -4500, 4500); // constrain output
pitch_pid_saturated = true; // freeze integrator next cycle
} else {
pitch_pid_saturated = false; // unfreeze integrator
}
g.rc_1.servo_out = roll_output;
g.rc_2.servo_out = pitch_output;
}
static int16_t
get_heli_rate_yaw(int32_t target_rate)
{
int32_t p,i,d,ff; // used to capture pid values for logging
int32_t current_rate; // this iteration's rate
int32_t rate_error;
int32_t output;
static bool pid_saturated; // tracker from last loop if the PID was saturated
current_rate = (omega.z * DEGX100); // get current rate
// rate control
rate_error = target_rate - current_rate;
// separately calculate p, i, d values for logging
p = g.pid_rate_yaw.get_p(rate_error);
if (pid_saturated){
i = g.pid_rate_yaw.get_integrator(); // Locked Integrator due to PID saturation on previous cycle
} else {
i = g.pid_rate_yaw.get_i(rate_error, G_Dt);
}
d = g.pid_rate_yaw.get_d(rate_error, G_Dt);
ff = g.heli_yaw_ff*target_rate;
output = p + i + d + ff;
if (labs(output) > 4500){
output = constrain_int32(output, -4500, 4500); // constrain output
pid_saturated = true; // freeze integrator next cycle
} else {
pid_saturated = false; // unfreeze integrator
}
#if LOGGING_ENABLED == ENABLED
// log output if PID loggins is on and we are tuning the yaw
if( g.log_bitmask & MASK_LOG_PID && (g.radio_tuning == CH6_YAW_RATE_KP || g.radio_tuning == CH6_YAW_RATE_KD) ) {
pid_log_counter++;
if( pid_log_counter >= 10 ) { // (update rate / desired output rate) = (100hz / 10hz) = 10
pid_log_counter = 0;
Log_Write_PID(CH6_YAW_RATE_KP, rate_error, p, i, d, output, tuning_value);
}
}
#endif
return output; // output control
}
#endif // HELI_FRAME
#if FRAME_CONFIG != HELI_FRAME
static int16_t
get_rate_roll(int32_t target_rate)
......@@ -922,7 +803,7 @@ static int16_t get_angle_boost(int16_t throttle)
{
float angle_boost_factor = cos_pitch_x * cos_roll_x;
angle_boost_factor = 1.0f - constrain_float(angle_boost_factor, .5f, 1.0f);
int16_t throttle_above_mid = max(throttle - motors.throttle_mid,0);
int16_t throttle_above_mid = max(throttle - motors.get_collective_mid(),0);
// to allow logging of angle boost
angle_boost = throttle_above_mid*angle_boost_factor;
......@@ -988,9 +869,8 @@ static void
set_throttle_takeoff()
{
// set alt target
if (controller_desired_alt < current_loc.alt) {
controller_desired_alt = current_loc.alt + ALT_HOLD_TAKEOFF_JUMP;
}
controller_desired_alt = current_loc.alt + ALT_HOLD_TAKEOFF_JUMP;
// clear i term from acceleration controller
if (g.pid_throttle_accel.get_integrator() < 0) {
g.pid_throttle_accel.reset_I();
......@@ -1037,8 +917,6 @@ get_throttle_accel(int16_t z_target_accel)
d = g.pid_throttle_accel.get_d(z_accel_error, .01f);
//
// limit the rate
output = constrain_float(p+i+d+g.throttle_cruise, g.throttle_min, g.throttle_max);
#if LOGGING_ENABLED == ENABLED
......
......@@ -8,7 +8,9 @@
#define __GCS_H
#include <AP_HAL.h>
#include <AP_Common.h>
#include <GPS.h>
#include <stdint.h>
///
/// @class GCS
......@@ -39,7 +41,6 @@ public:
///
void init(AP_HAL::UARTDriver *port) {
_port = port;
initialised = true;
}
/// Update GCS state.
......@@ -60,6 +61,14 @@ public:
void send_message(enum ap_message id) {
}
/// Send a text message.
///
/// @param severity A value describing the importance of the message.
/// @param str The text to be sent.
///
void send_text(gcs_severity severity, const char *str) {
}
/// Send a text message with a PSTR()
///
/// @param severity A value describing the importance of the message.
......@@ -122,6 +131,10 @@ public:
// see if we should send a stream now. Called at 50Hz
bool stream_trigger(enum streams stream_num);
// this costs us 51 bytes per instance, but means that low priority
// messages don't block the CPU
mavlink_statustext_t pending_status;
// call to reset the timeout window for entering the cli
void reset_cli_timeout();
private:
......@@ -140,6 +153,7 @@ private:
uint16_t _queued_parameter_count; ///< saved count of
// parameters for
// queued send
uint32_t _queued_parameter_send_time_ms;
/// Count the number of reportable parameters.
///
......@@ -179,16 +193,8 @@ private:
uint16_t waypoint_send_timeout; // milliseconds
uint16_t waypoint_receive_timeout; // milliseconds
// data stream rates
AP_Int16 streamRateRawSensors;
AP_Int16 streamRateExtendedStatus;
AP_Int16 streamRateRCChannels;
AP_Int16 streamRateRawController;
AP_Int16 streamRatePosition;
AP_Int16 streamRateExtra1;
AP_Int16 streamRateExtra2;
AP_Int16 streamRateExtra3;
AP_Int16 streamRateParams;
// saveable rate of each stream
AP_Int16 streamRates[NUM_STREAMS];
// number of 50Hz ticks until we next send this stream
uint8_t stream_ticks[NUM_STREAMS];
......
This diff is collapsed.
......@@ -208,7 +208,7 @@ static void Log_Write_AutoTuneDetails(int16_t angle_cd, float rate_cds)
struct PACKED log_Current {
LOG_PACKET_HEADER;
int16_t throttle_in;
int16_t throttle_out;
uint32_t throttle_integrator;
int16_t battery_voltage;
int16_t current_amps;
......@@ -221,7 +221,7 @@ static void Log_Write_Current()
{
struct log_Current pkt = {
LOG_PACKET_HEADER_INIT(LOG_CURRENT_MSG),
throttle_in : g.rc_3.control_in,
throttle_out : g.rc_3.servo_out,
throttle_integrator : throttle_integrator,
battery_voltage : (int16_t) (battery.voltage() * 100.0f),
current_amps : (int16_t) (battery.current_amps() * 100.0f),
......@@ -238,8 +238,7 @@ struct PACKED log_Motors {
#elif FRAME_CONFIG == HEXA_FRAME || FRAME_CONFIG == Y6_FRAME
int16_t motor_out[6];
#elif FRAME_CONFIG == HELI_FRAME
int16_t motor_out[4];
int16_t ext_gyro_gain;
int16_t motor_out[6];
#else // quads & TRI_FRAME
int16_t motor_out[4];
#endif
......@@ -270,13 +269,14 @@ static void Log_Write_Motors()
motor_out : {motors.motor_out[AP_MOTORS_MOT_1],
motors.motor_out[AP_MOTORS_MOT_2],
motors.motor_out[AP_MOTORS_MOT_3],
motors.motor_out[AP_MOTORS_MOT_4]},
ext_gyro_gain : motors.ext_gyro_gain
motors.motor_out[AP_MOTORS_MOT_4],
motors.motor_out[AP_MOTORS_MOT_7],
motors.motor_out[AP_MOTORS_MOT_8]}
#elif FRAME_CONFIG == TRI_FRAME
motor_out : {motors.motor_out[AP_MOTORS_MOT_1],
motors.motor_out[AP_MOTORS_MOT_2],
motors.motor_out[AP_MOTORS_MOT_4],
motors.motor_out[g.rc_4.radio_out]}
g.rc_4.radio_out}
#else // QUAD frame
motor_out : {motors.motor_out[AP_MOTORS_MOT_1],
motors.motor_out[AP_MOTORS_MOT_2],
......@@ -307,7 +307,7 @@ static void Log_Write_Optflow()
struct log_Optflow pkt = {
LOG_PACKET_HEADER_INIT(LOG_OPTFLOW_MSG),
dx : optflow.dx,
dy : optflow.dx,
dy : optflow.dy,
surface_quality : optflow.surface_quality,
x_cm : (int16_t) optflow.x_cm,
y_cm : (int16_t) optflow.y_cm,
......@@ -339,7 +339,7 @@ struct PACKED log_Nav_Tuning {
// Write an Nav Tuning packet
static void Log_Write_Nav_Tuning()
{
Vector3f velocity = inertial_nav.get_velocity();
const Vector3f &velocity = inertial_nav.get_velocity();
struct log_Nav_Tuning pkt = {
LOG_PACKET_HEADER_INIT(LOG_NAV_TUNING_MSG),
......@@ -427,12 +427,13 @@ struct PACKED log_Performance {
LOG_PACKET_HEADER;
uint8_t renorm_count;
uint8_t renorm_blowup;
uint8_t gps_fix_count;
uint16_t num_long_running;
uint16_t num_loops;
uint32_t max_time;
int16_t pm_test;
uint8_t i2c_lockup_count;
uint16_t ins_error_count;
uint8_t inav_error_count;
};
// Write a performance monitoring packet
......@@ -442,12 +443,13 @@ static void Log_Write_Performance()
LOG_PACKET_HEADER_INIT(LOG_PERFORMANCE_MSG),
renorm_count : ahrs.renorm_range_count,
renorm_blowup : ahrs.renorm_blowup_count,
gps_fix_count : gps_fix_count,
num_long_running : perf_info_get_num_long_running(),
num_loops : perf_info_get_num_loops(),
max_time : perf_info_get_max_time(),
pm_test : pmTest1,
i2c_lockup_count : hal.i2c->lockup_count()
i2c_lockup_count : hal.i2c->lockup_count(),
ins_error_count : ins.error_count(),
inav_error_count : inertial_nav.error_count()
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
......@@ -525,7 +527,7 @@ struct PACKED log_INAV {
// Write an INAV packet
static void Log_Write_INAV()
{
Vector3f accel_corr = inertial_nav.accel_correction_ef;
const Vector3f &accel_corr = inertial_nav.accel_correction_ef;
struct log_INAV pkt = {
LOG_PACKET_HEADER_INIT(LOG_INAV_MSG),
......@@ -715,6 +717,7 @@ static void Log_Write_PID(uint8_t pid_id, int32_t error, int32_t p, int32_t i, i
struct PACKED log_Camera {
LOG_PACKET_HEADER;
uint32_t gps_time;
uint16_t gps_week;
int32_t latitude;
int32_t longitude;
int32_t altitude;
......@@ -729,7 +732,8 @@ static void Log_Write_Camera()
#if CAMERA == ENABLED
struct log_Camera pkt = {
LOG_PACKET_HEADER_INIT(LOG_CAMERA_MSG),
gps_time : g_gps->time,
gps_time : g_gps->time_week_ms,
gps_week : g_gps->time_week,
latitude : current_loc.lat,
longitude : current_loc.lng,
altitude : current_loc.alt,
......@@ -767,7 +771,7 @@ static const struct LogStructure log_structure[] PROGMEM = {
"ATDE", "cf", "Angle,Rate" },
#endif
{ LOG_CURRENT_MSG, sizeof(log_Current),
"CURR", "hIhhhf", "Thr,ThrInt,Volt,Curr,Vcc,CurrTot" },
"CURR", "hIhhhf", "ThrOut,ThrInt,Volt,Curr,Vcc,CurrTot" },
#if FRAME_CONFIG == OCTA_FRAME || FRAME_CONFIG == OCTA_QUAD_FRAME
{ LOG_MOTORS_MSG, sizeof(log_Motors),
......@@ -792,7 +796,7 @@ static const struct LogStructure log_structure[] PROGMEM = {
{ LOG_COMPASS_MSG, sizeof(log_Compass),
"MAG", "hhhhhhhhh", "MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ" },
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
"PM", "BBBHHIhB", "RenCnt,RenBlw,FixCnt,NLon,NLoop,MaxT,PMT,I2CErr" },
"PM", "BBHHIhBHB", "RenCnt,RenBlw,NLon,NLoop,MaxT,PMT,I2CErr,INSErr,INAVErr" },
{ LOG_CMD_MSG, sizeof(log_Cmd),
"CMD", "BBBBBeLL", "CTot,CNum,CId,COpt,Prm1,Alt,Lat,Lng" },
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),
......@@ -818,7 +822,7 @@ static const struct LogStructure log_structure[] PROGMEM = {
{ LOG_PID_MSG, sizeof(log_PID),
"PID", "Biiiiif", "Id,Error,P,I,D,Out,Gain" },
{ LOG_CAMERA_MSG, sizeof(log_Camera),
"CAM", "ILLeccC", "GPSTime,Lat,Lng,Alt,Roll,Pitch,Yaw" },
"CAM", "IHLLeccC", "GPSTime,GPSWeek,Lat,Lng,Alt,Roll,Pitch,Yaw" },
{ LOG_ERROR_MSG, sizeof(log_Error),
"ERR", "BB", "Subsys,ECode" },
};
......@@ -830,7 +834,7 @@ static void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page)
cliSerial->printf_P(PSTR((AIRFRAME_NAME)));
#endif
cliSerial->printf_P(PSTR("\n" THISFIRMWARE
cliSerial->printf_P(PSTR("\n" FIRMWARE_STRING
"\nFree RAM: %u\n"),
(unsigned) memcheck_available_memory());
......@@ -849,6 +853,10 @@ static void start_logging()
if (g.log_bitmask != 0 && !ap.logging_started) {
ap.logging_started = true;
DataFlash.StartNewLog(sizeof(log_structure)/sizeof(log_structure[0]), log_structure);
DataFlash.Log_Write_Message_P(PSTR(FIRMWARE_STRING));
// log the flight mode
Log_Write_Mode(control_mode);
}
}
......
......@@ -73,11 +73,7 @@ public:
k_param_log_last_filenumber, // *** Deprecated - remove
// with next eeprom number
// change
k_param_toy_yaw_rate, // THOR The memory
// location for the
// Yaw Rate 1 = fast,
// 2 = med, 3 = slow
k_param_toy_yaw_rate, // deprecated - remove
k_param_crosstrack_min_distance, // deprecated - remove with next eeprom number change
k_param_rssi_pin,
k_param_throttle_accel_enabled, // deprecated - remove
......@@ -92,7 +88,8 @@ public:
k_param_angle_max,
k_param_gps_hdop_good,
k_param_battery,
k_param_fs_batt_mah, // 37
k_param_fs_batt_mah,
k_param_angle_rate_max, // 38
// 65: AP_Limits Library
k_param_limits = 65, // deprecated - remove
......@@ -102,6 +99,14 @@ public:
k_param_fence,
k_param_gps_glitch, // 70
//
// 75: Singlecopter
//
k_param_single_servo_1 = 75,
k_param_single_servo_2,
k_param_single_servo_3,
k_param_single_servo_4, // 78
//
// 80: Heli
//
......@@ -109,9 +114,11 @@ public:
k_param_heli_servo_2,
k_param_heli_servo_3,
k_param_heli_servo_4,
k_param_heli_pitch_ff,
k_param_heli_roll_ff,
k_param_heli_yaw_ff,
k_param_heli_pitch_ff,
k_param_heli_roll_ff,
k_param_heli_yaw_ff,
k_param_heli_stab_col_min,
k_param_heli_stab_col_max, // 88
//
// 90: Motors
......@@ -127,11 +134,13 @@ public:
// 110: Telemetry control
//
k_param_gcs0 = 110,
k_param_gcs3,
k_param_gcs1,
k_param_sysid_this_mav,
k_param_sysid_my_gcs,
k_param_serial3_baud,
k_param_serial1_baud,
k_param_telem_delay,
k_param_gcs2,
k_param_serial2_baud,
//
// 140: Sensor parameters
......@@ -274,7 +283,10 @@ public:
//
AP_Int16 sysid_this_mav;
AP_Int16 sysid_my_gcs;
AP_Int8 serial3_baud;
AP_Int8 serial1_baud;
#if MAVLINK_COMM_NUM_BUFFERS > 2
AP_Int8 serial2_baud;
#endif
AP_Int8 telem_delay;
AP_Int16 rtl_altitude;
......@@ -287,7 +299,7 @@ public:
AP_Int8 failsafe_battery_enabled; // battery failsafe enabled
AP_Float fs_batt_voltage; // battery voltage below which failsafe will be triggered
AP_Float fs_batt_mah; // battery capacity (in mah) below which failsafe will be triggered
AP_Int8 failsafe_gps_enabled; // gps failsafe enabled
AP_Int8 failsafe_gcs; // ground station failsafe behavior
AP_Int16 gps_hdop_good; // GPS Hdop value at or below this value represent a good position
......@@ -302,6 +314,7 @@ public:
AP_Int8 rssi_pin;
AP_Int8 wp_yaw_behavior; // controls how the autopilot controls yaw during missions
AP_Int16 angle_max; // maximum lean angle of the copter in centi-degrees
AP_Int32 angle_rate_max; // maximum rotation rate in roll/pitch axis requested by angle controller used in stabilize, loiter, rtl, auto flight modes
// Waypoints
//
......@@ -336,12 +349,6 @@ public:
// Misc
//
AP_Int16 log_bitmask;
AP_Int8 toy_yaw_rate; // THOR The
// Yaw Rate 1
// = fast, 2 =
// med, 3 =
// slow
AP_Int8 esc_calibrate;
AP_Int8 radio_tuning;
AP_Int16 radio_tuning_high;
......@@ -356,7 +363,13 @@ public:
RC_Channel heli_servo_1, heli_servo_2, heli_servo_3, heli_servo_4; // servos for swash plate and tail
AP_Float heli_pitch_ff; // pitch rate feed-forward
AP_Float heli_roll_ff; // roll rate feed-forward
AP_Float heli_yaw_ff; // yaw rate feed-forward
AP_Float heli_yaw_ff; // yaw rate feed-forward
AP_Int16 heli_stab_col_min; // min collective while pilot directly controls collective in stabilize mode
AP_Int16 heli_stab_col_max; // min collective while pilot directly controls collective in stabilize mode
#endif
#if FRAME_CONFIG == SINGLE_FRAME
// Single
RC_Channel single_servo_1, single_servo_2, single_servo_3, single_servo_4; // servos for four flaps
#endif
// RC channels
......@@ -368,11 +381,8 @@ public:
RC_Channel_aux rc_6;
RC_Channel_aux rc_7;
RC_Channel_aux rc_8;
#if MOUNT == ENABLED
RC_Channel_aux rc_10;
RC_Channel_aux rc_11;
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
RC_Channel_aux rc_9;
......@@ -417,6 +427,12 @@ public:
heli_servo_3 (CH_3),
heli_servo_4 (CH_4),
#endif
#if FRAME_CONFIG == SINGLE_FRAME
single_servo_1 (CH_1),
single_servo_2 (CH_2),
single_servo_3 (CH_3),
single_servo_4 (CH_4),
#endif
rc_1 (CH_1),
rc_2 (CH_2),
......@@ -428,12 +444,11 @@ public:
rc_8 (CH_8),
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
rc_9 (CH_9),
#endif
rc_10 (CH_10),
rc_11 (CH_11),
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
rc_12 (CH_12),
#elif MOUNT == ENABLED
rc_10 (CH_10),
rc_11 (CH_11),
#endif
// PID controller initial P initial I initial D
......
......@@ -22,6 +22,7 @@
#define GSCALAR(v, name, def) { g.v.vtype, name, Parameters::k_param_ ## v, &g.v, {def_value : def} }
#define GGROUP(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &g.v, {group_info : class::var_info} }
#define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &v, {group_info : class::var_info} }
#define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, &v, {group_info : class::var_info} }
const AP_Param::Info var_info[] PROGMEM = {
// @Param: SYSID_SW_MREV
......@@ -48,12 +49,21 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Advanced
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),
// @Param: SERIAL3_BAUD
// @Param: SERIAL1_BAUD
// @DisplayName: Telemetry Baud Rate
// @Description: The baud rate used on the telemetry port
// @Description: The baud rate used on the first telemetry port
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200
// @User: Standard
GSCALAR(serial3_baud, "SERIAL3_BAUD", SERIAL3_BAUD/1000),
GSCALAR(serial1_baud, "SERIAL1_BAUD", SERIAL1_BAUD/1000),
#if MAVLINK_COMM_NUM_BUFFERS > 2
// @Param: SERIAL2_BAUD
// @DisplayName: Telemetry Baud Rate
// @Description: The baud rate used on the seconds telemetry port
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200
// @User: Standard
GSCALAR(serial2_baud, "SERIAL2_BAUD", SERIAL2_BAUD/1000),
#endif
// @Param: TELEM_DELAY
// @DisplayName: Telemetry startup delay
......@@ -98,14 +108,15 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: FS_BATT_ENABLE
// @DisplayName: Battery Failsafe Enable
// @Description: Controls whether failsafe will be invoked when battery voltage or current runs low
// @Values: 0:Disabled,1:Enabled
// @Values: 0:Disabled,1:Land,2:RTL
// @User: Standard
GSCALAR(failsafe_battery_enabled, "FS_BATT_ENABLE", FS_BATTERY),
GSCALAR(failsafe_battery_enabled, "FS_BATT_ENABLE", FS_BATT_DISABLED),
// @Param: FS_BATT_VOLTAGE
// @DisplayName: Failsafe battery voltage
// @Description: Battery voltage to trigger failsafe. Set to 0 to disable battery voltage failsafe. If the battery voltage drops below this voltage then the copter will RTL
// @Units: Volts
// @Increment: 0.1
// @User: Standard
GSCALAR(fs_batt_voltage, "FS_BATT_VOLTAGE", FS_BATT_VOLTAGE_DEFAULT),
......@@ -113,15 +124,16 @@ const AP_Param::Info var_info[] PROGMEM = {
// @DisplayName: Failsafe battery milliAmpHours
// @Description: Battery capacity remaining to trigger failsafe. Set to 0 to disable battery remaining failsafe. If the battery remaining drops below this level then the copter will RTL
// @Units: mAh
// @Increment: 50
// @User: Standard
GSCALAR(fs_batt_mah, "FS_BATT_MAH", FS_BATT_MAH_DEFAULT),
// @Param: FS_GPS_ENABLE
// @DisplayName: GPS Failsafe Enable
// @Description: Controls whether failsafe will be invoked when gps signal is lost
// @Values: 0:Disabled,1:Enabled
// @Description: Controls what action will be taken if GPS signal is lost for at least 5 seconds
// @Values: 0:Disabled,1:Land,2:AltHold,3:Land even from Stabilize
// @User: Standard
GSCALAR(failsafe_gps_enabled, "FS_GPS_ENABLE", FS_GPS),
GSCALAR(failsafe_gps_enabled, "FS_GPS_ENABLE", FS_GPS_LAND),
// @Param: FS_GCS_ENABLE
// @DisplayName: Ground Station Failsafe Enable
......@@ -224,7 +236,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @DisplayName: Land speed
// @Description: The descent speed for the final stage of landing in cm/s
// @Units: cm/s
// @Range: 20 200
// @Range: 30 200
// @Increment: 10
// @User: Standard
GSCALAR(land_speed, "LAND_SPEED", LAND_SPEED),
......@@ -292,42 +304,42 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: FLTMODE1
// @DisplayName: Flight Mode 1
// @Description: Flight mode when Channel 5 pwm is <= 1230
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:ToyA,12:ToyM,13:Sport
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:Drift,13:Sport
// @User: Standard
GSCALAR(flight_mode1, "FLTMODE1", FLIGHT_MODE_1),
// @Param: FLTMODE2
// @DisplayName: Flight Mode 2
// @Description: Flight mode when Channel 5 pwm is >1230, <= 1360
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:ToyA,12:ToyM,13:Sport
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:Drift,13:Sport
// @User: Standard
GSCALAR(flight_mode2, "FLTMODE2", FLIGHT_MODE_2),
// @Param: FLTMODE3
// @DisplayName: Flight Mode 3
// @Description: Flight mode when Channel 5 pwm is >1360, <= 1490
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:ToyA,12:ToyM,13:Sport
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:Drift,13:Sport
// @User: Standard
GSCALAR(flight_mode3, "FLTMODE3", FLIGHT_MODE_3),
// @Param: FLTMODE4
// @DisplayName: Flight Mode 4
// @Description: Flight mode when Channel 5 pwm is >1490, <= 1620
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:ToyA,12:ToyM,13:Sport
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:Drift,13:Sport
// @User: Standard
GSCALAR(flight_mode4, "FLTMODE4", FLIGHT_MODE_4),
// @Param: FLTMODE5
// @DisplayName: Flight Mode 5
// @Description: Flight mode when Channel 5 pwm is >1620, <= 1749
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:ToyA,12:ToyM,13:Sport
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:Drift,13:Sport
// @User: Standard
GSCALAR(flight_mode5, "FLTMODE5", FLIGHT_MODE_5),
// @Param: FLTMODE6
// @DisplayName: Flight Mode 6
// @Description: Flight mode when Channel 5 pwm is >=1750
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:ToyA,12:ToyM,13:Sport
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,8:Position,9:Land,10:OF_Loiter,11:Drift,13:Sport
// @User: Standard
GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6),
......@@ -344,13 +356,6 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Advanced
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
// @Param: TOY_RATE
// @DisplayName: Toy Yaw Rate
// @Description: Controls yaw rate in Toy mode. Higher values will cause a slower yaw rate. Do not set to zero!
// @User: Advanced
// @Range: 1 10
GSCALAR(toy_yaw_rate, "TOY_RATE", 1),
// @Param: ESC
// @DisplayName: ESC Calibration
// @Description: Controls whether ArduCopter will enter ESC calibration on the next restart. Do not adjust this parameter manually.
......@@ -402,10 +407,10 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: ARMING_CHECK
// @DisplayName: Arming check
// @Description: Allows enabling or disabling of pre-arming checks of receiver, accelerometer, barometer and compass
// @Values: 0:Disabled, 1:Enabled
// @Description: Allows enabling or disabling of pre-arming checks of receiver, accelerometer, barometer, compass and GPS
// @Values: 0:Disabled, 1:Enabled, -3:Skip Baro, -5:Skip Compass, -9:Skip GPS, -17:Skip INS, -33:Skip Parameters, -65:Skip RC, 127:Skip Voltage
// @User: Standard
GSCALAR(arming_check_enabled, "ARMING_CHECK", 1),
GSCALAR(arming_check_enabled, "ARMING_CHECK", ARMING_CHECK_ALL),
// @Param: ANGLE_MAX
// @DisplayName: Angle Max
......@@ -414,6 +419,13 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Advanced
GSCALAR(angle_max, "ANGLE_MAX", DEFAULT_ANGLE_MAX),
// @Param: ANGLE_RATE_MAX
// @DisplayName: Angle Rate max
// @Description: maximum rotation rate in roll/pitch axis requested by angle controller used in stabilize, loiter, rtl, auto flight modes
// @Range 90000 250000
// @User: Advanced
GSCALAR(angle_rate_max, "ANGLE_RATE_MAX", ANGLE_RATE_MAX),
#if FRAME_CONFIG == HELI_FRAME
// @Group: HS1_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
......@@ -432,6 +444,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @DisplayName: Rate Pitch Feed Forward
// @Description: Rate Pitch Feed Forward (for TradHeli Only)
// @Range: 0 10
// @Increment: 0.01
// @User: Standard
GSCALAR(heli_pitch_ff, "RATE_PIT_FF", HELI_PITCH_FF),
......@@ -439,6 +452,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @DisplayName: Rate Roll Feed Forward
// @Description: Rate Roll Feed Forward (for TradHeli Only)
// @Range: 0 10
// @Increment: 0.01
// @User: Standard
GSCALAR(heli_roll_ff, "RATE_RLL_FF", HELI_ROLL_FF),
......@@ -446,10 +460,45 @@ const AP_Param::Info var_info[] PROGMEM = {
// @DisplayName: Rate Yaw Feed Forward
// @Description: Rate Yaw Feed Forward (for TradHeli Only)
// @Range: 0 10
// @Increment: 0.01
// @User: Standard
GSCALAR(heli_yaw_ff, "RATE_YAW_FF", HELI_YAW_FF),
// @Param: H_STAB_COL_MIN
// @DisplayName: Heli Stabilize Throttle Collective Minimum
// @Description: Helicopter's minimum collective position while pilot directly controls collective in stabilize mode
// @Range: 0 500
// @Units: pwm
// @Increment: 1
// @User: Standard
GSCALAR(heli_stab_col_min, "H_STAB_COL_MIN", HELI_STAB_COLLECTIVE_MIN_DEFAULT),
// @Param: H_STAB_COL_MAX
// @DisplayName: Stabilize Throttle Maximum
// @Description: Helicopter's maximum collective position while pilot directly controls collective in stabilize mode
// @Range: 500 1000
// @Units: pwm
// @Increment: 1
// @User: Standard
GSCALAR(heli_stab_col_max, "H_STAB_COL_MAX", HELI_STAB_COLLECTIVE_MAX_DEFAULT),
#endif
#if FRAME_CONFIG == SINGLE_FRAME
// @Group: SS1_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP(single_servo_1, "SS1_", RC_Channel),
// @Group: SS2_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP(single_servo_2, "SS2_", RC_Channel),
// @Group: SS3_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP(single_servo_3, "SS3_", RC_Channel),
// @Group: SS4_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP(single_servo_4, "SS4_", RC_Channel),
#endif
// RC channel
//-----------
// @Group: RC1_
......@@ -477,20 +526,20 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_8, "RC8_", RC_Channel_aux),
#if MOUNT == ENABLED
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
// @Group: RC9_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_9, "RC9_", RC_Channel_aux),
#endif
// @Group: RC10_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_10, "RC10_", RC_Channel_aux),
// @Group: RC11_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_11, "RC11_", RC_Channel_aux),
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
// @Group: RC9_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_9, "RC9_", RC_Channel_aux),
// @Group: RC12_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_12, "RC12_", RC_Channel_aux),
......@@ -929,7 +978,6 @@ const AP_Param::Info var_info[] PROGMEM = {
// variables not in the g class which contain EEPROM saved variables
// variables not in the g class which contain EEPROM saved variables
#if CAMERA == ENABLED
// @Group: CAM_
// @Path: ../libraries/AP_Camera/AP_Camera.cpp
......@@ -960,11 +1008,17 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Group: SR0_
// @Path: GCS_Mavlink.pde
GOBJECT(gcs0, "SR0_", GCS_MAVLINK),
GOBJECTN(gcs[0], gcs0, "SR0_", GCS_MAVLINK),
// @Group: SR3_
// @Group: SR1_
// @Path: GCS_Mavlink.pde
GOBJECT(gcs3, "SR3_", GCS_MAVLINK),
GOBJECTN(gcs[1], gcs1, "SR1_", GCS_MAVLINK),
#if MAVLINK_COMM_NUM_BUFFERS > 2
// @Group: SR2_
// @Path: GCS_Mavlink.pde
GOBJECTN(gcs[2], gcs2, "SR2_", GCS_MAVLINK),
#endif
// @Group: AHRS_
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
......@@ -1018,6 +1072,24 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Group: H_
// @Path: ../libraries/AP_Motors/AP_MotorsHeli.cpp
GOBJECT(motors, "H_", AP_MotorsHeli),
#elif FRAME_CONFIG == SINGLE_FRAME
// @Group: SS1_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP(single_servo_1, "SS1_", RC_Channel),
// @Group: SS2_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP(single_servo_2, "SS2_", RC_Channel),
// @Group: SS3_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP(single_servo_3, "SS3_", RC_Channel),
// @Group: SS4_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP(single_servo_4, "SS4_", RC_Channel),
// @Group: (SingleCopter)MOT_
// @Path: ../libraries/AP_Motors/AP_MotorsSingle.cpp
GOBJECT(motors, "MOT_", AP_MotorsSingle),
#else
// @Group: MOT_
// @Path: ../libraries/AP_Motors/AP_Motors_Class.cpp
......