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 (164)
Showing
with 401 additions and 124 deletions
......@@ -958,6 +958,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
{
// mark the firmware version in the tlog
send_text_P(SEVERITY_LOW, PSTR(FIRMWARE_STRING));
#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
send_text_P(SEVERITY_LOW, PSTR("PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION));
#endif
handle_param_request_list(msg);
break;
}
......
......@@ -19,10 +19,6 @@
*/
// uncomment the lines below to save on flash space if compiling for the APM using Arduino IDE. Top items save the most flash space
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_APM1)
# define CLI_ENABLED DISABLED // disable the CLI (command-line-interface) to save 21K of flash space
# define FRSKY_TELEM_ENABLED DISABLED // disable the FRSKY TELEM
#endif
//#define LOGGING_ENABLED DISABLED // disable dataflash logging to save 11K of flash space
//#define MOUNT DISABLED // disable the camera gimbal to save 8K of flash space
//#define AUTOTUNE_ENABLED DISABLED // disable the auto tune functionality to save 7k of flash
......@@ -34,6 +30,7 @@
// features below are disabled by default on APM (but enabled on Pixhawk)
//#define AC_RALLY ENABLED // disable rally points to save 2k of flash, and also frees rally point EEPROM for more mission commands
//#define PARACHUTE ENABLED // enable parachute release at a cost of 1k of flash
//#define CLI_ENABLED ENABLED // enable the CLI (command-line-interface) at a cost of 21K of flash space
// features below are disabled by default on all boards
//#define OPTFLOW ENABLED // enable optical flow sensor and OF_LOITER flight mode at a cost of 5K of flash space
......
......@@ -110,6 +110,21 @@ void set_land_complete(bool b)
// ---------------------------------------------
// set land complete maybe flag
void set_land_complete_maybe(bool b)
{
// if no change, exit immediately
if (ap.land_complete_maybe == b)
return;
if (b) {
Log_Write_Event(DATA_LAND_COMPLETE_MAYBE);
}
ap.land_complete_maybe = b;
}
// ---------------------------------------------
void set_pre_arm_check(bool b)
{
if(ap.pre_arm_check != b) {
......
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define THISFIRMWARE "ArduCopter V3.2-rc5"
#define THISFIRMWARE "ArduCopter V3.2-rc13"
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
......@@ -206,6 +206,9 @@ static AP_Notify notify;
// used to detect MAVLink acks from GCS to stop compassmot
static uint8_t command_ack_counter;
// has a log download started?
static bool in_log_download;
////////////////////////////////////////////////////////////////////////////////
// prototypes
////////////////////////////////////////////////////////////////////////////////
......@@ -388,6 +391,8 @@ static union {
uint8_t rc_receiver_present : 1; // 14 // true if we have an rc receiver present (i.e. if we've ever received an update
uint8_t compass_mot : 1; // 15 // true if we are currently performing compassmot calibration
uint8_t motor_test : 1; // 16 // true if we are currently performing the motors test
uint8_t initialised : 1; // 17 // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
uint8_t land_complete_maybe : 1; // 18 // true if we may have landed (less strict version of land_complete)
};
uint32_t value;
} ap;
......@@ -571,8 +576,8 @@ static int16_t climb_rate;
static int16_t sonar_alt;
static uint8_t sonar_alt_health; // true if we can trust the altitude from the sonar
static float target_sonar_alt; // desired altitude in cm above the ground
// The altitude as reported by Baro in cm - Values can be quite high
static int32_t baro_alt;
static int32_t baro_alt; // barometer altitude in cm above home
static float baro_climbrate; // barometer climbrate in cm/s
////////////////////////////////////////////////////////////////////////////////
......@@ -805,7 +810,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
#endif
{ update_notify, 8, 10 },
{ one_hz_loop, 400, 42 },
{ ekf_check, 40, 2 },
{ ekf_dcm_check, 40, 2 },
{ crash_check, 40, 2 },
{ gcs_check_input, 8, 550 },
{ gcs_send_heartbeat, 400, 150 },
......@@ -873,7 +878,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
#endif
{ update_notify, 2, 100 },
{ one_hz_loop, 100, 420 },
{ ekf_check, 10, 20 },
{ ekf_dcm_check, 10, 20 },
{ crash_check, 10, 20 },
{ gcs_check_input, 2, 550 },
{ gcs_send_heartbeat, 100, 150 },
......@@ -942,7 +947,7 @@ static void barometer_accumulate(void)
static void perf_update(void)
{
if (g.log_bitmask & MASK_LOG_PM)
if (should_log(MASK_LOG_PM))
Log_Write_Performance();
if (scheduler.debug()) {
cliSerial->printf_P(PSTR("PERF: %u/%u %lu\n"),
......@@ -1089,7 +1094,7 @@ static void update_batt_compass(void)
compass.set_throttle((float)g.rc_3.servo_out/1000.0f);
compass.read();
// log compass information
if (g.log_bitmask & MASK_LOG_COMPASS) {
if (should_log(MASK_LOG_COMPASS)) {
Log_Write_Compass();
}
}
......@@ -1102,16 +1107,16 @@ static void update_batt_compass(void)
// should be run at 10hz
static void ten_hz_logging_loop()
{
if (g.log_bitmask & MASK_LOG_ATTITUDE_MED) {
if (should_log(MASK_LOG_ATTITUDE_MED)) {
Log_Write_Attitude();
}
if (g.log_bitmask & MASK_LOG_RCIN) {
if (should_log(MASK_LOG_RCIN)) {
DataFlash.Log_Write_RCIN();
}
if (g.log_bitmask & MASK_LOG_RCOUT) {
if (should_log(MASK_LOG_RCOUT)) {
DataFlash.Log_Write_RCOUT();
}
if ((g.log_bitmask & MASK_LOG_NTUN) && mode_requires_GPS(control_mode)) {
if (should_log(MASK_LOG_NTUN) && (mode_requires_GPS(control_mode) || landing_with_GPS())) {
Log_Write_Nav_Tuning();
}
}
......@@ -1126,11 +1131,11 @@ static void fifty_hz_logging_loop()
#endif
#if HIL_MODE == HIL_MODE_DISABLED
if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST) {
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
Log_Write_Attitude();
}
if (g.log_bitmask & MASK_LOG_IMU) {
if (should_log(MASK_LOG_IMU)) {
DataFlash.Log_Write_IMU(ins);
}
#endif
......@@ -1160,12 +1165,12 @@ static void three_hz_loop()
// one_hz_loop - runs at 1Hz
static void one_hz_loop()
{
if (g.log_bitmask != 0) {
if (should_log(MASK_LOG_ANY)) {
Log_Write_Data(DATA_AP_STATE, ap.value);
}
// log battery info to the dataflash
if (g.log_bitmask & MASK_LOG_CURRENT) {
if (should_log(MASK_LOG_CURRENT)) {
Log_Write_Current();
}
......@@ -1224,7 +1229,7 @@ static void update_optical_flow(void)
of_log_counter++;
if( of_log_counter >= 4 ) {
of_log_counter = 0;
if (g.log_bitmask & MASK_LOG_OPTFLOW) {
if (should_log(MASK_LOG_OPTFLOW)) {
Log_Write_Optflow();
}
}
......@@ -1248,7 +1253,7 @@ static void update_GPS(void)
last_gps_reading[i] = gps.last_message_time_ms(i);
// log GPS message
if (g.log_bitmask & MASK_LOG_GPS) {
if (should_log(MASK_LOG_GPS)) {
DataFlash.Log_Write_GPS(gps, i, current_loc.alt);
}
......@@ -1334,7 +1339,7 @@ init_simple_bearing()
super_simple_sin_yaw = simple_sin_yaw;
// log the simple bearing to dataflash
if (g.log_bitmask != 0) {
if (should_log(MASK_LOG_ANY)) {
Log_Write_Data(DATA_INIT_SIMPLE_BEARING, ahrs.yaw_sensor);
}
}
......@@ -1399,13 +1404,13 @@ static void read_AHRS(void)
static void update_altitude()
{
// read in baro altitude
baro_alt = read_barometer();
read_barometer();
// read in sonar altitude
sonar_alt = read_sonar();
// write altitude info to dataflash logs
if (g.log_bitmask & MASK_LOG_CTUN) {
if (should_log(MASK_LOG_CTUN)) {
Log_Write_Control_Tuning();
}
}
......
......@@ -151,8 +151,8 @@ static int16_t get_pilot_desired_throttle(int16_t throttle_control)
// get_pilot_desired_climb_rate - transform pilot's throttle input to
// climb rate in cm/s. we use radio_in instead of control_in to get the full range
// without any deadzone at the bottom
#define THROTTLE_IN_DEADBAND_TOP (THROTTLE_IN_MIDDLE+THROTTLE_IN_DEADBAND) // top of the deadband
#define THROTTLE_IN_DEADBAND_BOTTOM (THROTTLE_IN_MIDDLE-THROTTLE_IN_DEADBAND) // bottom of the deadband
#define THROTTLE_IN_DEADBAND_TOP (THROTTLE_IN_MIDDLE+g.throttle_deadzone) // top of the deadband
#define THROTTLE_IN_DEADBAND_BOTTOM (THROTTLE_IN_MIDDLE-g.throttle_deadzone) // bottom of the deadband
static int16_t get_pilot_desired_climb_rate(int16_t throttle_control)
{
int16_t desired_rate = 0;
......@@ -165,13 +165,16 @@ static int16_t get_pilot_desired_climb_rate(int16_t throttle_control)
// ensure a reasonable throttle value
throttle_control = constrain_int16(throttle_control,0,1000);
// ensure a reasonable deadzone
g.throttle_deadzone = constrain_int16(g.throttle_deadzone, 0, 400);
// check throttle is above, below or in the deadband
if (throttle_control < THROTTLE_IN_DEADBAND_BOTTOM) {
// below the deadband
desired_rate = (int32_t)g.pilot_velocity_z_max * (throttle_control-THROTTLE_IN_DEADBAND_BOTTOM) / (THROTTLE_IN_MIDDLE - THROTTLE_IN_DEADBAND);
desired_rate = (int32_t)g.pilot_velocity_z_max * (throttle_control-THROTTLE_IN_DEADBAND_BOTTOM) / (THROTTLE_IN_MIDDLE - g.throttle_deadzone);
}else if (throttle_control > THROTTLE_IN_DEADBAND_TOP) {
// above the deadband
desired_rate = (int32_t)g.pilot_velocity_z_max * (throttle_control-THROTTLE_IN_DEADBAND_TOP) / (THROTTLE_IN_MIDDLE - THROTTLE_IN_DEADBAND);
desired_rate = (int32_t)g.pilot_velocity_z_max * (throttle_control-THROTTLE_IN_DEADBAND_TOP) / (THROTTLE_IN_MIDDLE - g.throttle_deadzone);
}else{
// must be in the deadband
desired_rate = 0;
......
......@@ -199,11 +199,14 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
if (ap.rc_receiver_present && !failsafe.radio) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
}
if (!ins.healthy()) {
control_sensors_health &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
if (!ins.get_gyro_health_all() || !ins.gyro_calibrated_ok_all()) {
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_GYRO;
}
if (!ins.get_accel_health_all()) {
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_ACCEL;
}
if (!ahrs.healthy()) {
if (ahrs.initialised() && !ahrs.healthy()) {
// AHRS subsystem is unhealthy
control_sensors_health &= ~MAV_SYS_STATUS_AHRS;
}
......@@ -221,9 +224,10 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
case AP_Terrain::TerrainStatusDisabled:
break;
case AP_Terrain::TerrainStatusUnhealthy:
control_sensors_present |= MAV_SYS_STATUS_TERRAIN;
control_sensors_enabled |= MAV_SYS_STATUS_TERRAIN;
break;
// To-Do: restore unhealthy terrain status reporting once terrain is used in copter
//control_sensors_present |= MAV_SYS_STATUS_TERRAIN;
//control_sensors_enabled |= MAV_SYS_STATUS_TERRAIN;
//break;
case AP_Terrain::TerrainStatusOK:
control_sensors_present |= MAV_SYS_STATUS_TERRAIN;
control_sensors_enabled |= MAV_SYS_STATUS_TERRAIN;
......@@ -276,8 +280,7 @@ static void NOINLINE send_location(mavlink_channel_t chan)
static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
{
Vector3f targets;
get_angle_targets_for_reporting(targets);
const Vector3f &targets = attitude_control.angle_ef_targets();
mavlink_msg_nav_controller_output_send(
chan,
targets.x / 1.0e2f,
......@@ -479,10 +482,14 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
break;
case MSG_EXTENDED_STATUS1:
CHECK_PAYLOAD_SIZE(SYS_STATUS);
send_extended_status1(chan);
CHECK_PAYLOAD_SIZE(POWER_STATUS);
gcs[chan-MAVLINK_COMM_0].send_power_status();
// send extended status only once vehicle has been initialised
// to avoid unnecessary errors being reported to user
if (ap.initialised) {
CHECK_PAYLOAD_SIZE(SYS_STATUS);
send_extended_status1(chan);
CHECK_PAYLOAD_SIZE(POWER_STATUS);
gcs[chan-MAVLINK_COMM_0].send_power_status();
}
break;
case MSG_EXTENDED_STATUS2:
......@@ -877,6 +884,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
mavlink_set_mode_t packet;
mavlink_msg_set_mode_decode(msg, &packet);
// exit immediately if this command is not meant for this vehicle
if (mavlink_check_target(packet.target_system, 0)) {
break;
}
// only accept custom modes because there is no easy mapping from Mavlink flight modes to AC flight modes
if (packet.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
if (set_mode(packet.custom_mode)) {
......@@ -897,6 +909,13 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: // MAV ID: 21
{
// mark the firmware version in the tlog
send_text_P(SEVERITY_LOW, PSTR(FIRMWARE_STRING));
#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
send_text_P(SEVERITY_LOW, PSTR("PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION));
#endif
send_text_P(SEVERITY_LOW, PSTR("Frame: " FRAME_CONFIG_STRING));
handle_param_request_list(msg);
break;
}
......@@ -1044,12 +1063,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case MAV_CMD_CONDITION_YAW:
// param1 : target angle [0-360]
// param2 : speed during change [deg per second]
// param3 : direction (not supported)
// param3 : direction (-1:ccw, +1:cw)
// param4 : relative offset (1) or absolute angle (0)
if ((packet.param1 >= 0.0f) &&
(packet.param1 <= 360.0f) &&
((packet.param4 == 0) || (packet.param4 == 1))) {
set_auto_yaw_look_at_heading(packet.param1, packet.param2, (uint8_t)packet.param4);
set_auto_yaw_look_at_heading(packet.param1, packet.param2, (int8_t)packet.param3, (uint8_t)packet.param4);
result = MAV_RESULT_ACCEPTED;
} else {
result = MAV_RESULT_FAILED;
......@@ -1091,10 +1110,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
case MAV_CMD_PREFLIGHT_CALIBRATION:
if (packet.param1 == 1 ||
packet.param2 == 1) {
ins.init_accel();
ahrs.set_trim(Vector3f(0,0,0)); // clear out saved trim
if (packet.param1 == 1) {
// gyro offset calibration
ins.init_gyro();
result = MAV_RESULT_ACCEPTED;
}
if (packet.param3 == 1) {
......@@ -1279,11 +1297,21 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case MAVLINK_MSG_ID_RADIO:
case MAVLINK_MSG_ID_RADIO_STATUS: // MAV ID: 109
{
handle_radio_status(msg, DataFlash, (g.log_bitmask & MASK_LOG_PM) != 0);
handle_radio_status(msg, DataFlash, should_log(MASK_LOG_PM));
break;
}
case MAVLINK_MSG_ID_LOG_REQUEST_LIST ... MAVLINK_MSG_ID_LOG_REQUEST_END: // MAV ID: 117 ... 122
case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
case MAVLINK_MSG_ID_LOG_ERASE:
in_log_download = true;
// fallthru
case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
if (!in_mavlink_delay && !motors.armed()) {
handle_log_message(msg, DataFlash);
}
break;
case MAVLINK_MSG_ID_LOG_REQUEST_END:
in_log_download = false;
if (!in_mavlink_delay && !motors.armed()) {
handle_log_message(msg, DataFlash);
}
......
......@@ -173,7 +173,7 @@ struct PACKED log_AutoTune {
float new_gain_sp; // newly calculated gain
};
// Write an Current data packet
// Write an Autotune data packet
static void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float rate_min, float rate_max, float new_gain_rp, float new_gain_rd, float new_gain_sp)
{
struct log_AutoTune pkt = {
......@@ -195,7 +195,7 @@ struct PACKED log_AutoTuneDetails {
float rate_cds; // current rotation rate in centi-degrees / second
};
// Write an Current data packet
// Write an Autotune data packet
static void Log_Write_AutoTuneDetails(int16_t angle_cd, float rate_cds)
{
struct log_AutoTuneDetails pkt = {
......@@ -464,13 +464,14 @@ struct PACKED log_Attitude {
int16_t pitch;
uint16_t control_yaw;
uint16_t yaw;
uint16_t error_rp;
uint16_t error_yaw;
};
// Write an attitude packet
static void Log_Write_Attitude()
{
Vector3f targets;
get_angle_targets_for_reporting(targets);
const Vector3f &targets = attitude_control.angle_ef_targets();
struct log_Attitude pkt = {
LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),
time_ms : hal.scheduler->millis(),
......@@ -479,7 +480,9 @@ static void Log_Write_Attitude()
control_pitch : (int16_t)targets.y,
pitch : (int16_t)ahrs.pitch_sensor,
control_yaw : (uint16_t)targets.z,
yaw : (uint16_t)ahrs.yaw_sensor
yaw : (uint16_t)ahrs.yaw_sensor,
error_rp : (uint16_t)(ahrs.get_error_rp() * 100),
error_yaw : (uint16_t)(ahrs.get_error_yaw() * 100)
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
......@@ -530,7 +533,7 @@ struct PACKED log_Event {
// Wrote an event packet
static void Log_Write_Event(uint8_t id)
{
if (g.log_bitmask != 0) {
if (should_log(MASK_LOG_ANY)) {
struct log_Event pkt = {
LOG_PACKET_HEADER_INIT(LOG_EVENT_MSG),
id : id
......@@ -548,7 +551,7 @@ struct PACKED log_Data_Int16t {
// Write an int16_t data packet
static void Log_Write_Data(uint8_t id, int16_t value)
{
if (g.log_bitmask != 0) {
if (should_log(MASK_LOG_ANY)) {
struct log_Data_Int16t pkt = {
LOG_PACKET_HEADER_INIT(LOG_DATA_INT16_MSG),
id : id,
......@@ -567,7 +570,7 @@ struct PACKED log_Data_UInt16t {
// Write an uint16_t data packet
static void Log_Write_Data(uint8_t id, uint16_t value)
{
if (g.log_bitmask != 0) {
if (should_log(MASK_LOG_ANY)) {
struct log_Data_UInt16t pkt = {
LOG_PACKET_HEADER_INIT(LOG_DATA_UINT16_MSG),
id : id,
......@@ -586,7 +589,7 @@ struct PACKED log_Data_Int32t {
// Write an int32_t data packet
static void Log_Write_Data(uint8_t id, int32_t value)
{
if (g.log_bitmask != 0) {
if (should_log(MASK_LOG_ANY)) {
struct log_Data_Int32t pkt = {
LOG_PACKET_HEADER_INIT(LOG_DATA_INT32_MSG),
id : id,
......@@ -605,7 +608,7 @@ struct PACKED log_Data_UInt32t {
// Write a uint32_t data packet
static void Log_Write_Data(uint8_t id, uint32_t value)
{
if (g.log_bitmask != 0) {
if (should_log(MASK_LOG_ANY)) {
struct log_Data_UInt32t pkt = {
LOG_PACKET_HEADER_INIT(LOG_DATA_UINT32_MSG),
id : id,
......@@ -624,7 +627,7 @@ struct PACKED log_Data_Float {
// Write a float data packet
static void Log_Write_Data(uint8_t id, float value)
{
if (g.log_bitmask != 0) {
if (should_log(MASK_LOG_ANY)) {
struct log_Data_Float pkt = {
LOG_PACKET_HEADER_INIT(LOG_DATA_FLOAT_MSG),
id : id,
......@@ -685,7 +688,7 @@ static const struct LogStructure log_structure[] PROGMEM = {
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
"PM", "HHIhBHB", "NLon,NLoop,MaxT,PMT,I2CErr,INSErr,INAVErr" },
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),
"ATT", "IccccCC", "TimeMS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw" },
"ATT", "IccccCCCC", "TimeMS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw,ErrRP,ErrYaw" },
{ LOG_MODE_MSG, sizeof(log_Mode),
"MODE", "Mh", "Mode,ThrCrs" },
{ LOG_STARTUP_MSG, sizeof(log_Startup),
......@@ -715,7 +718,8 @@ static void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page)
#endif
cliSerial->printf_P(PSTR("\n" FIRMWARE_STRING
"\nFree RAM: %u\n"),
"\nFree RAM: %u\n"
"\nFrame: " FRAME_CONFIG_STRING "\n"),
(unsigned) hal.util->available_memory());
cliSerial->println_P(PSTR(HAL_BOARD_NAME));
......@@ -746,6 +750,7 @@ static void start_logging()
if (hal.util->get_system_id(sysid)) {
DataFlash.Log_Write_Message(sysid);
}
DataFlash.Log_Write_Message_P(PSTR("Frame: " FRAME_CONFIG_STRING));
// log the flight mode
Log_Write_Mode(control_mode);
......
......@@ -81,7 +81,7 @@ public:
// Misc
//
k_param_log_bitmask = 20,
k_param_log_bitmask_old = 20, // Deprecated
k_param_log_last_filenumber, // *** Deprecated - remove
// with next eeprom number
// change
......@@ -119,7 +119,11 @@ public:
k_param_sonar, // sonar object
k_param_ekfcheck_thresh,
k_param_terrain,
k_param_acro_expo, // 56
k_param_acro_expo,
k_param_throttle_deadzone,
k_param_optflow,
k_param_dcmcheck_thresh, // 59
k_param_log_bitmask,
// 65: AP_Limits Library
k_param_limits = 65, // deprecated - remove
......@@ -365,6 +369,7 @@ public:
AP_Int16 failsafe_throttle_value;
AP_Int16 throttle_cruise;
AP_Int16 throttle_mid;
AP_Int16 throttle_deadzone;
// Flight modes
//
......@@ -378,7 +383,7 @@ public:
// Misc
//
AP_Int16 log_bitmask;
AP_Int32 log_bitmask;
AP_Int8 esc_calibrate;
AP_Int8 radio_tuning;
AP_Int16 radio_tuning_high;
......@@ -390,6 +395,7 @@ public:
AP_Int8 land_repositioning;
AP_Float ekfcheck_thresh;
AP_Float dcmcheck_thresh;
#if FRAME_CONFIG == HELI_FRAME
// Heli
......
......@@ -295,6 +295,15 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Increment: 1
GSCALAR(throttle_mid, "THR_MID", THR_MID_DEFAULT),
// @Param: THR_DZ
// @DisplayName: Throttle deadzone
// @Description: The deadzone above and below mid throttle. Used in AltHold, Loiter, PosHold flight modes
// @User: Standard
// @Range: 0 300
// @Units: pwm
// @Increment: 1
GSCALAR(throttle_deadzone, "THR_DZ", THR_DZ_DEFAULT),
// @Param: FLTMODE1
// @DisplayName: Flight Mode 1
// @Description: Flight mode when Channel 5 pwm is <= 1230
......@@ -345,8 +354,8 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: LOG_BITMASK
// @DisplayName: Log bitmask
// @Description: 2 byte bitmap of log types to enable
// @Values: 830:Default,894:Default+RCIN,958:Default+IMU,1854:Default+Motors,-6146:NearlyAll,0:Disabled
// @Description: 4 byte bitmap of log types to enable
// @Values: 830:Default,894:Default+RCIN,958:Default+IMU,1854:Default+Motors,-6146:NearlyAll-AC315,43006:NearlyAll,131070:All+DisarmedLogging,0:Disabled
// @User: Standard
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
......@@ -381,7 +390,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: FRAME
// @DisplayName: Frame Orientation (+, X or V)
// @Description: Controls motor mixing for multicopters. Not used for Tri or Traditional Helicopters.
// @Values: 0:Plus, 1:X, 2:V, 3:H, 4:V-Tail, 10:Y6B (New)
// @Values: 0:Plus, 1:X, 2:V, 3:H, 4:V-Tail, 5:A-Tail, 10:Y6B (New)
// @User: Standard
GSCALAR(frame_orientation, "FRAME", AP_MOTORS_X_FRAME),
......@@ -447,12 +456,19 @@ const AP_Param::Info var_info[] PROGMEM = {
GSCALAR(land_repositioning, "LAND_REPOSITION", LAND_REPOSITION_DEFAULT),
// @Param: EKF_CHECK_THRESH
// @DisplayName: EKF and InertialNav check compass and velocity variance threshold
// @DisplayName: EKF check compass and velocity variance threshold
// @Description: Allows setting the maximum acceptable compass and velocity variance (0 to disable check)
// @Values: 0:Disabled, 0.6:Default, 1.0:Relaxed
// @User: Advanced
GSCALAR(ekfcheck_thresh, "EKF_CHECK_THRESH", EKFCHECK_THRESHOLD_DEFAULT),
// @Param: DCM_CHECK_THRESH
// @DisplayName: DCM yaw error threshold
// @Description: Allows setting the maximum acceptable yaw error as a sin of the yaw error (0 to disable check)
// @Values: 0:Disabled, 0.8:Default, 0.98:Relaxed
// @User: Advanced
GSCALAR(dcmcheck_thresh, "DCM_CHECK_THRESH", DCMCHECK_THRESHOLD_DEFAULT),
#if FRAME_CONFIG == HELI_FRAME
// @Group: HS1_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
......@@ -589,7 +605,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: ACRO_EXPO
// @DisplayName: Acro Expo
// @Description: Acro roll/pitch Expo to allow faster rotation when stick at edges
// @Values: 0:Disabled,0.2:Low,0.3:Medium,0.4:High
// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
// @User: Advanced
GSCALAR(acro_expo, "ACRO_EXPO", ACRO_EXPO_DEFAULT),
......@@ -799,7 +815,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: THR_ACCEL_IMAX
// @DisplayName: Throttle acceleration controller I gain maximum
// @Description: Throttle acceleration controller I gain maximum. Constrains the maximum pwm that the I term will generate
// @Range: 0 500
// @Range: 0 1000
// @Units: Percent*10
// @User: Standard
......@@ -993,7 +1009,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Group: BRD_
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),
GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),
#if SPRAYER == ENABLED
// @Group: SPRAY_
......@@ -1126,12 +1142,13 @@ const AP_Param::ConversionInfo conversion_table[] PROGMEM = {
{ Parameters::k_param_volt_div_ratio, 0, AP_PARAM_FLOAT, "BATT_VOLT_MULT" },
{ Parameters::k_param_curr_amp_per_volt, 0, AP_PARAM_FLOAT, "BATT_AMP_PERVOLT" },
{ Parameters::k_param_pack_capacity, 0, AP_PARAM_INT32, "BATT_CAPACITY" },
{ Parameters::k_param_log_bitmask_old, 0, AP_PARAM_INT16, "LOG_BITMASK" },
};
static void load_parameters(void)
{
if (!AP_Param::check_var_info()) {
cliSerial->printf_P(PSTR("Bad var table\n"));
cliSerial->printf_P(PSTR("Bad var table\n"));
hal.scheduler->panic(PSTR("Bad var table"));
}
......
ArduCopter Release Notes:
------------------------------------------------------------------
ArduCopter 3.2-rc13 23-Oct-2014
Changes from 3.2-rc12
1) DCM check triggers LAND if yaw disagrees with GPS by > 60deg (configure with DCM_CHECK_THRESH param) and in Loiter, PosHold, Auto, etc
2) Safety features:
a) landing detector checks baro climbrate between -1.5 ~ +1.5 m/s
b) sanity check AHRS_RP_P and AHRS_YAW_P are never less than 0.05
c) check set-mode requests from GCS are for this vehicle
3) Bug fixes:
a) fix ch6 tuning of wp-speed (was getting stuck at zero)
b) parachute servo set to off position on startup
c) Auto Takeoff timing bug fix that could cause severe lean on takeoff
d) timer fix for "slow start" of motors on Pixhawk (timer was incorrectly based on 100hz APM2 main loop speed)
4) reduced number of relays from 4 to 2 (saves memory and flash required on APM boards)
5) reduced number of range finders from 2 to 1 (saves memory and flash on APM boards)
6) allow logging from startup when LOG_BITMASK set to "All+DisarmedLogging"
------------------------------------------------------------------
ArduCopter 3.2-rc12 10-Oct-2014
Changes from 3.2-rc11
1) disable sonar on APM1 and TradHeli (APM1 & APM2) to allow code to fit
2) Add pre-arm and health check that gyro calibration succeeded
3) Bug fix to EKF reporting invalid position and velocity when switched on in flight with Ch7/Ch8 switch
------------------------------------------------------------------
ArduCopter 3.2-rc11 06-Oct-2014
Changes from 3.2-rc10
1) reduce lean on take-off in Auto by resetting horizontal position targets
2) TradHeli landing check ignores overall throttle output
3) reduce AHRS bad messages by delaying 20sec after init to allow EKF to settle (Pixhawk only)
4) Bug fixes:
a) fix THR_MIN scaling issue that could cause landing-detector to fail to detect landing when ch3 min~max > 1000 pwm
b) fix Mediatek GPS configuration so update rate is set correctly to 5hz
c) fix to Condition-Yaw mission command to support relative angles
d) EKF bug fixes when recovering from GPS glitches (affects only Pixhawks using EKF)
------------------------------------------------------------------
ArduCopter 3.2-rc10 24-Sep-2014
Changes from 3.2-rc9
1) two-stage land-detector to reduce motor run-up when landing in Loiter, PosHold, RTL, Auto
2) Allow passthrough from input to output of channels 9 ~ 14 (thanks Emile!)
3) Add 4hz filter to vertical velocity error during AltHold
4) Safety Feature:
a) increase Alt Disparity pre-arm check threshold to 2m (was 1m)
b) reset battery failsafe after disarming/arming (thanks AndKe!)
c) EKF only apply centrifugal corrections when GPS has at least 6 satellites (Pixhawk with EKF enabled only)
5) Bug fixes:
a) to default compass devid to zero when no compass connected
b) reduce motor run-up while landing in RTL
------------------------------------------------------------------
ArduCopter 3.2-rc9 11-Sep-2014
Changes from 3.2-rc8
1) FRAM bug fix that could stop Mission or Parameter changes from being saved (Pixhawk, VRBrain only)
------------------------------------------------------------------
ArduCopter 3.2-rc8 11-Sep-2014
Changes from 3.2-rc7
1) EKF reduced ripple to resolve copter motor pulsing
2) Default Param changes:
a) AltHold Rate P reduced from 6 to 5
b) AltHold Accel P reduced from 0.75 to 0.5, I from 1.5 to 1.0
c) EKF check threshold increased from 0.6 to 0.8 to reduce false positives
3) sensor health flags sent to GCS only after initialisation to remove false alerts
4) suppress bad terrain data alerts
5) Bug Fix:
a)PX4 dataflash RAM useage reduced to 8k so it works again
------------------------------------------------------------------
ArduCopter 3.2-rc7 04-Sep-2014
Changes from 3.2-rc6
1) Safety Items:
a) Landing check made more strict (climb rate requirement reduced to 30cm/s, overall throttle < 25%, rotation < 20deg/sec)
b) pre-arm check that accels are consistent (Pixhawk only, must be within 1m/sec/sec of each other)
c) pre-arm check that gyros are consistent (Pixhawk only, must be within 20deg/sec of each other)
d) report health of all accels and gyros (not just primary) to ground station
------------------------------------------------------------------
ArduCopter 3.2-rc6 31-Aug-2014
Changes from 3.2-rc5
1) Spline twitch when passing through a waypoint largely resolved
2) THR_DZ param added to allow user configuration of throttle deadzone during AltHold, Loiter, PosHold
3) Landing check made more strict (climb rate must be -40~40cm/s for 1 full second)
4) LAND_REPOSITION param default set to 1
5) TradHeli with flybar passes through pilot inputs directly to swash when in ACRO mode
6) Safety Items:
a) EKF check disabled when using inertial nav (caused too many false positives)
b) pre-arm check of internal vs external compass direction (must be within 45deg of each other)
7) Bug Fixes:
a) resolve NaN in angle targets when vehicle hits gimbal lock in ACRO mode
b) resolve GPS driver buffer overflow that could lead to missed GPS messages on Pixhawk/PX4 boards
c) resolve false "compass not calibrated" warnings on Pixhawk/PX4 caused by missing device id initialisation
------------------------------------------------------------------
ArduCopter 3.2-rc5 15-Aug-2014
Changes from 3.2-rc4
1) Pixhawk's max num waypoints increased to 718
......
......@@ -14,7 +14,7 @@ static void init_home()
inertial_nav.setup_home_position();
// log new home position which mission library will pull from ahrs
if (g.log_bitmask & MASK_LOG_CMD) {
if (should_log(MASK_LOG_CMD)) {
AP_Mission::Mission_Command temp_cmd;
if (mission.read_cmd_from_storage(0, temp_cmd)) {
Log_Write_Cmd(temp_cmd);
......
......@@ -33,7 +33,7 @@ static void auto_spline_start(const Vector3f& destination, bool stopped_at_start
static bool start_command(const AP_Mission::Mission_Command& cmd)
{
// To-Do: logging when new commands start/end
if (g.log_bitmask & MASK_LOG_CMD) {
if (should_log(MASK_LOG_CMD)) {
Log_Write_Cmd(cmd);
}
......@@ -151,16 +151,6 @@ static bool start_command(const AP_Mission::Mission_Command& cmd)
break;
#endif
#if MOUNT == ENABLED
case MAV_CMD_DO_MOUNT_CONFIGURE: // Mission command to configure a camera mount |Mount operation mode (see MAV_CONFIGURE_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty|
camera_mount.configure_cmd();
break;
case MAV_CMD_DO_MOUNT_CONTROL: // Mission command to control a camera mount |pitch(deg*100) or lat, depending on mount mode.| roll(deg*100) or lon depending on mount mode| yaw(deg*100) or alt (in cm) depending on mount mode| Empty| Empty| Empty| Empty|
camera_mount.control_cmd();
break;
#endif
#if PARACHUTE == ENABLED
case MAV_CMD_DO_PARACHUTE: // Mission command to configure or release parachute
do_parachute(cmd);
......@@ -782,6 +772,7 @@ static void do_yaw(const AP_Mission::Mission_Command& cmd)
set_auto_yaw_look_at_heading(
cmd.content.yaw.angle_deg,
cmd.content.yaw.turn_rate_dps,
cmd.content.yaw.direction,
cmd.content.yaw.relative_angle);
}
......@@ -913,7 +904,7 @@ static void do_take_picture()
{
#if CAMERA == ENABLED
camera.trigger_pic();
if (g.log_bitmask & MASK_LOG_CAMERA) {
if (should_log(MASK_LOG_CAMERA)) {
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
}
#endif
......
......@@ -84,6 +84,13 @@
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75
# define PARACHUTE DISABLED
# define AC_RALLY DISABLED
# define CLI_ENABLED DISABLED
# define FRSKY_TELEM_ENABLED DISABLED
#endif
// disable sonar on APM1 and TradHeli/APM2
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || (CONFIG_HAL_BOARD == HAL_BOARD_APM2 && FRAME_CONFIG == HELI_FRAME))
# define CONFIG_SONAR DISABLED
#endif
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75 || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
......@@ -110,6 +117,28 @@
# define FRAME_CONFIG QUAD_FRAME
#endif
#if FRAME_CONFIG == QUAD_FRAME
# define FRAME_CONFIG_STRING "QUAD"
#elif FRAME_CONFIG == TRI_FRAME
# define FRAME_CONFIG_STRING "TRI"
#elif FRAME_CONFIG == HEXA_FRAME
# define FRAME_CONFIG_STRING "HEXA"
#elif FRAME_CONFIG == Y6_FRAME
# define FRAME_CONFIG_STRING "Y6"
#elif FRAME_CONFIG == OCTA_FRAME
# define FRAME_CONFIG_STRING "OCTA"
#elif FRAME_CONFIG == OCTA_QUAD_FRAME
# define FRAME_CONFIG_STRING "OCTA_QUAD"
#elif FRAME_CONFIG == HELI_FRAME
# define FRAME_CONFIG_STRING "HELI"
#elif FRAME_CONFIG == SINGLE_FRAME
# define FRAME_CONFIG_STRING "SINGLE"
#elif FRAME_CONFIG == COAX_FRAME
# define FRAME_CONFIG_STRING "COAX"
#else
# define FRAME_CONFIG_STRING "UNKNOWN"
#endif
/////////////////////////////////////////////////////////////////////////////////
// TradHeli defaults
#if FRAME_CONFIG == HELI_FRAME
......@@ -299,15 +328,33 @@
#define FS_GCS_ENABLED_ALWAYS_RTL 1
#define FS_GCS_ENABLED_CONTINUE_MISSION 2
// pre-arm baro vs inertial nav max alt disparity
#ifndef PREARM_MAX_ALT_DISPARITY_CM
# define PREARM_MAX_ALT_DISPARITY_CM 200 // barometer and inertial nav altitude must be within this many centimeters
#endif
// pre-arm check max velocity
#ifndef PREARM_MAX_VELOCITY_CMS
# define PREARM_MAX_VELOCITY_CMS 50.0f // vehicle must be travelling under 50cm/s before arming
#endif
// arming check's maximum acceptable accelerometer vector difference (in m/s/s) between primary and backup accelerometers
#ifndef PREARM_MAX_ACCEL_VECTOR_DIFF
#define PREARM_MAX_ACCEL_VECTOR_DIFF 1.0f // pre arm accel check will fail if primary and backup accelerometer vectors differ by 1m/s/s
#endif
// arming check's maximum acceptable rotation rate difference (in rad/sec) between primary and backup gyros
#ifndef PREARM_MAX_GYRO_VECTOR_DIFF
#define PREARM_MAX_GYRO_VECTOR_DIFF 0.35f // pre arm gyro check will fail if primary and backup gyro vectors differ by 0.35 rad/sec (=20deg/sec)
#endif
//////////////////////////////////////////////////////////////////////////////
// EKF Checker
// EKF & DCM Checker
#ifndef EKFCHECK_THRESHOLD_DEFAULT
# define EKFCHECK_THRESHOLD_DEFAULT 0.6f // EKF checker's default compass and velocity variance above which the EKF's horizontal position will be considered bad
# define EKFCHECK_THRESHOLD_DEFAULT 0.8f // EKF checker's default compass and velocity variance above which the EKF's horizontal position will be considered bad
#endif
#ifndef DCMCHECK_THRESHOLD_DEFAULT
# define DCMCHECK_THRESHOLD_DEFAULT 0.8f // DCM checker's default yaw error threshold above which we will abandon horizontal position hold. The units are sin(angle) so 0.8 = about 60degrees of error
#endif
//////////////////////////////////////////////////////////////////////////////
......@@ -338,6 +385,11 @@
#endif
#endif
// arming check's maximum acceptable vector difference between internal and external compass after vectors are normalized to field length of 1.0
#ifndef COMPASS_ACCEPTABLE_VECTOR_DIFF
#define COMPASS_ACCEPTABLE_VECTOR_DIFF 0.75 // pre arm compass check will fail if internal vs external compass direction differ by more than 45 degrees
#endif
//////////////////////////////////////////////////////////////////////////////
// OPTICAL_FLOW
#ifndef OPTFLOW // sets global enabled/disabled flag for optflow (as seen in CLI)
......@@ -442,11 +494,23 @@
#ifndef LAND_DETECTOR_TRIGGER
# define LAND_DETECTOR_TRIGGER 50 // number of 50hz iterations with near zero climb rate and low throttle that triggers landing complete.
#endif
#ifndef LAND_DETECTOR_MAYBE_TRIGGER
# define LAND_DETECTOR_MAYBE_TRIGGER 10 // number of 50hz iterations with near zero climb rate and low throttle that means we might be landed (used to reset horizontal position targets to prevent tipping over)
#endif
#ifndef LAND_DETECTOR_CLIMBRATE_MAX
# define LAND_DETECTOR_CLIMBRATE_MAX 30 // vehicle climb rate must be between -30 and +30 cm/s
#endif
#ifndef LAND_DETECTOR_BARO_CLIMBRATE_MAX
# define LAND_DETECTOR_BARO_CLIMBRATE_MAX 150 // barometer climb rate must be between -150cm/s ~ +150cm/s
#endif
#ifndef LAND_DETECTOR_ROTATION_MAX
# define LAND_DETECTOR_ROTATION_MAX 0.50f // vehicle rotation must be below 0.5 rad/sec (=30deg/sec for) vehicle to consider itself landed
#endif
#ifndef LAND_REQUIRE_MIN_THROTTLE_TO_DISARM // require pilot to reduce throttle to minimum before vehicle will disarm
# define LAND_REQUIRE_MIN_THROTTLE_TO_DISARM ENABLED
#endif
#ifndef LAND_REPOSITION_DEFAULT
# define LAND_REPOSITION_DEFAULT 0 // by default the pilot cannot override roll/pitch during landing
# define LAND_REPOSITION_DEFAULT 1 // by default the pilot can override roll/pitch during landing
#endif
#ifndef LAND_WITH_DELAY_MS
# define LAND_WITH_DELAY_MS 4000 // default delay (in milliseconds) when a land-with-delay is triggered during a failsafe event
......@@ -584,7 +648,7 @@
# define RATE_PITCH_D 0.004f
#endif
#ifndef RATE_PITCH_IMAX
# define RATE_PITCH_IMAX 500
# define RATE_PITCH_IMAX 1000
#endif
#ifndef RATE_YAW_P
......@@ -654,8 +718,8 @@
# define THR_MAX_DEFAULT 1000 // maximum throttle sent to the motors
#endif
#ifndef THROTTLE_IN_DEADBAND
# define THROTTLE_IN_DEADBAND 100 // the throttle input channel's deadband in PWM
#ifndef THR_DZ_DEFAULT
# define THR_DZ_DEFAULT 100 // the deadzone above and below mid throttle while in althold or loiter
#endif
#ifndef ALT_HOLD_P
......@@ -664,7 +728,21 @@
// RATE control
#ifndef THROTTLE_RATE_P
# define THROTTLE_RATE_P 6.0f
# define THROTTLE_RATE_P 5.0f
#endif
// Throttle Accel control
#ifndef THROTTLE_ACCEL_P
# define THROTTLE_ACCEL_P 0.50f
#endif
#ifndef THROTTLE_ACCEL_I
# define THROTTLE_ACCEL_I 1.00f
#endif
#ifndef THROTTLE_ACCEL_D
# define THROTTLE_ACCEL_D 0.0f
#endif
#ifndef THROTTLE_ACCEL_IMAX
# define THROTTLE_ACCEL_IMAX 800
#endif
// default maximum vertical velocity and acceleration the pilot may request
......@@ -684,20 +762,6 @@
# define ALT_HOLD_ACCEL_MAX 250 // if you change this you must also update the duplicate declaration in AC_WPNav.h
#endif
// Throttle Accel control
#ifndef THROTTLE_ACCEL_P
# define THROTTLE_ACCEL_P 0.75f
#endif
#ifndef THROTTLE_ACCEL_I
# define THROTTLE_ACCEL_I 1.50f
#endif
#ifndef THROTTLE_ACCEL_D
# define THROTTLE_ACCEL_D 0.0f
#endif
#ifndef THROTTLE_ACCEL_IMAX
# define THROTTLE_ACCEL_IMAX 500
#endif
//////////////////////////////////////////////////////////////////////////////
// Dataflash logging control
//
......
......@@ -59,6 +59,11 @@ static void get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in, int
// expo variables
float rp_in, rp_in3, rp_out;
// range check expo
if (g.acro_expo > 1.0f) {
g.acro_expo = 1.0f;
}
// roll expo
rp_in = float(roll_in)/ROLL_PITCH_INPUT_MAX;
rp_in3 = rp_in*rp_in*rp_in;
......
......@@ -102,13 +102,14 @@ static void auto_takeoff_run()
{
// if not auto armed set throttle to zero and exit immediately
if(!ap.auto_armed) {
// initialise wpnav targets
wp_nav.shift_wp_origin_to_current_pos();
// reset attitude control targets
attitude_control.relax_bf_rate_controller();
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
// tell motors to do a slow start
motors.slow_start(true);
// To-Do: re-initialise wpnav targets
return;
}
......@@ -287,6 +288,11 @@ static void auto_land_run()
return;
}
// relax loiter targets if we might be landed
if (land_complete_maybe()) {
wp_nav.loiter_soften_for_landing();
}
// process pilot's input
if (!failsafe.radio) {
if (g.land_repositioning) {
......@@ -470,7 +476,7 @@ void set_auto_yaw_mode(uint8_t yaw_mode)
}
// set_auto_yaw_look_at_heading - sets the yaw look at heading for auto mode
static void set_auto_yaw_look_at_heading(float angle_deg, float turn_rate_dps, uint8_t relative_angle)
static void set_auto_yaw_look_at_heading(float angle_deg, float turn_rate_dps, int8_t direction, uint8_t relative_angle)
{
// get current yaw target
int32_t curr_yaw_target = attitude_control.angle_ef_targets().z;
......@@ -481,7 +487,10 @@ static void set_auto_yaw_look_at_heading(float angle_deg, float turn_rate_dps, u
yaw_look_at_heading = wrap_360_cd(angle_deg * 100);
} else {
// relative angle
yaw_look_at_heading = wrap_360_cd(angle_deg * 100);
if (direction < 0) {
angle_deg = -angle_deg;
}
yaw_look_at_heading = wrap_360_cd((angle_deg*100+curr_yaw_target));
}
// get turn speed
......
......@@ -53,10 +53,10 @@
#define AUTOTUNE_PI_RATIO_FOR_TESTING 0.1f // I is set 10x smaller than P during testing
#define AUTOTUNE_RP_RATIO_FINAL 1.0f // I is set 1x P after testing
#define AUTOTUNE_RD_MIN 0.002f // minimum Rate D value
#define AUTOTUNE_RD_MAX 0.015f // maximum Rate D value
#define AUTOTUNE_RD_MAX 0.020f // maximum Rate D value
#define AUTOTUNE_RP_MIN 0.01f // minimum Rate P value
#define AUTOTUNE_RP_MAX 0.25f // maximum Rate P value
#define AUTOTUNE_SP_MAX 15.0f // maximum Stab P value
#define AUTOTUNE_RP_MAX 0.35f // maximum Rate P value
#define AUTOTUNE_SP_MAX 20.0f // maximum Stab P value
#define AUTOTUNE_SUCCESS_COUNT 4 // how many successful iterations we need to freeze at current gains
// Auto Tune message ids for ground station
......
......@@ -64,6 +64,7 @@ void guided_pos_control_start()
set_auto_yaw_mode(get_default_auto_yaw_mode(false));
}
#if NAV_GUIDED == ENABLED
// initialise guided mode's velocity controller
void guided_vel_control_start()
{
......@@ -77,6 +78,7 @@ void guided_vel_control_start()
// initialise velocity controller
pos_control.init_vel_controller_xyz();
}
#endif
// guided_set_destination - sets guided mode's target destination
static void guided_set_destination(const Vector3f& destination)
......@@ -89,6 +91,7 @@ static void guided_set_destination(const Vector3f& destination)
wp_nav.set_wp_destination(destination);
}
#if NAV_GUIDED == ENABLED
// guided_set_velocity - sets guided mode's target velocity
static void guided_set_velocity(const Vector3f& velocity)
{
......@@ -100,6 +103,7 @@ static void guided_set_velocity(const Vector3f& velocity)
// set position controller velocity target
pos_control.set_desired_velocity(velocity);
}
#endif
// guided_run - runs the guided controller
// should be called at 100hz or more
......@@ -128,9 +132,12 @@ static void guided_run()
guided_pos_control_run();
break;
#if NAV_GUIDED == ENABLED
case Guided_Velocity:
// run velocity controller
guided_vel_control_run();
break;
#endif
}
}
......@@ -140,13 +147,14 @@ static void guided_takeoff_run()
{
// if not auto armed set throttle to zero and exit immediately
if(!ap.auto_armed) {
// initialise wpnav targets
wp_nav.shift_wp_origin_to_current_pos();
// reset attitude control targets
attitude_control.relax_bf_rate_controller();
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
// tell motors to do a slow start
motors.slow_start(true);
// To-Do: re-initialise wpnav targets
return;
}
......
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// counter to verify landings
static uint16_t land_detector;
static uint16_t land_detector = LAND_DETECTOR_TRIGGER; // we assume we are landed
static bool land_with_gps;
static uint32_t land_start_time;
......@@ -73,6 +73,11 @@ static void land_gps_run()
return;
}
// relax loiter target if we might be landed
if (land_complete_maybe()) {
wp_nav.loiter_soften_for_landing();
}
// process pilot inputs
if (!failsafe.radio) {
if (g.land_repositioning) {
......@@ -187,31 +192,44 @@ static float get_throttle_land()
}
}
// land_complete_maybe - return true if we may have landed (used to reset loiter targets during landing)
static bool land_complete_maybe()
{
return (ap.land_complete || ap.land_complete_maybe);
}
// update_land_detector - checks if we have landed and updates the ap.land_complete flag
// returns true if we have landed
static bool update_land_detector()
// called at 50hz
static void update_land_detector()
{
// detect whether we have landed by watching for low climb rate and minimum throttle
if (abs(climb_rate) < 40 && motors.limit.throttle_lower) {
// detect whether we have landed by watching for low climb rate, motors hitting their lower limit, overall low throttle and low rotation rate
if ((abs(climb_rate) < LAND_DETECTOR_CLIMBRATE_MAX) &&
(abs(baro_climbrate) < LAND_DETECTOR_BARO_CLIMBRATE_MAX) &&
motors.limit.throttle_lower &&
#if FRAME_CONFIG != HELI_FRAME
(motors.get_throttle_out() < get_non_takeoff_throttle()) &&
#endif
(ahrs.get_gyro().length() < LAND_DETECTOR_ROTATION_MAX)) {
if (!ap.land_complete) {
// run throttle controller if accel based throttle controller is enabled and active (active means it has been given a target)
// increase counter until we hit the trigger then set land complete flag
if( land_detector < LAND_DETECTOR_TRIGGER) {
land_detector++;
}else{
set_land_complete(true);
land_detector = 0;
land_detector = LAND_DETECTOR_TRIGGER;
}
}
} else if ((motors.get_throttle_out() > get_non_takeoff_throttle()) || failsafe.radio) {
} else {
// we've sensed movement up or down so reset land_detector
land_detector = 0;
if(ap.land_complete) {
// if throttle output is high then clear landing flag
if (motors.get_throttle_out() > get_non_takeoff_throttle()) {
set_land_complete(false);
}
}
// return current state of landing
return ap.land_complete;
// set land maybe flag
set_land_complete_maybe(land_detector >= LAND_DETECTOR_MAYBE_TRIGGER);
}
// land_do_not_use_GPS - forces land-mode to not use the GPS but instead rely on pilot input for roll and pitch
......@@ -228,3 +246,8 @@ static void set_mode_land_with_pause()
set_mode(LAND);
land_pause = true;
}
// landing_with_GPS - returns true if vehicle is landing using GPS
static bool landing_with_GPS() {
return (control_mode == LAND && land_with_gps);
}
......@@ -68,6 +68,11 @@ static void loiter_run()
wp_nav.clear_pilot_desired_acceleration();
}
// relax loiter target if we might be landed
if (land_complete_maybe()) {
wp_nav.loiter_soften_for_landing();
}
// when landed reset targets and output zero throttle
if (ap.land_complete) {
wp_nav.init_loiter_target();
......
......@@ -183,6 +183,11 @@ static void poshold_run()
}
}
// relax loiter target if we might be landed
if (land_complete_maybe()) {
wp_nav.loiter_soften_for_landing();
}
// if landed initialise loiter targets, set throttle to zero and exit
if (ap.land_complete) {
wp_nav.init_loiter_target();
......