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 (57)
Showing
with 340 additions and 380 deletions
language: cpp
before_install:
- cd .. && ./ardupilot/Tools/scripts/install-prereqs-ubuntu.sh -y && . ~/.profile
- APMDIR=$(pwd) && pushd .. && $APMDIR/Tools/scripts/install-prereqs-ubuntu.sh -y && . ~/.profile && popd
script:
- cd ./ardupilot && Tools/scripts/build_all_travis.sh
- Tools/scripts/build_all_travis.sh
notifications:
webhooks:
......
......@@ -201,21 +201,7 @@ static AP_GPS gps;
// flight modes convenience array
static AP_Int8 *modes = &g.mode1;
#if CONFIG_BARO == HAL_BARO_BMP085
static AP_Baro_BMP085 barometer;
#elif CONFIG_BARO == HAL_BARO_PX4
static AP_Baro_PX4 barometer;
#elif CONFIG_BARO == HAL_BARO_VRBRAIN
static AP_Baro_VRBRAIN barometer;
#elif CONFIG_BARO == HAL_BARO_HIL
static AP_Baro_HIL barometer;
#elif CONFIG_BARO == HAL_BARO_MS5611
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::i2c);
#elif CONFIG_BARO == HAL_BARO_MS5611_SPI
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::spi);
#else
#error Unrecognized CONFIG_BARO setting
#endif
static AP_Baro barometer;
#if CONFIG_COMPASS == HAL_COMPASS_PX4
static AP_Compass_PX4 compass;
......@@ -639,7 +625,7 @@ static void mount_update(void)
static void update_alt()
{
barometer.read();
barometer.update();
if (should_log(MASK_LOG_IMU)) {
Log_Write_Baro();
}
......
......@@ -117,21 +117,7 @@ void gcs_send_text_fmt(const prog_char_t *fmt, ...);
////////////////////////////////////////////////////////////////////////////////
static AP_GPS gps;
#if CONFIG_BARO == HAL_BARO_BMP085
static AP_Baro_BMP085 barometer;
#elif CONFIG_BARO == HAL_BARO_PX4
static AP_Baro_PX4 barometer;
#elif CONFIG_BARO == HAL_BARO_VRBRAIN
static AP_Baro_VRBRAIN barometer;
#elif CONFIG_BARO == HAL_BARO_HIL
static AP_Baro_HIL barometer;
#elif CONFIG_BARO == HAL_BARO_MS5611
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::i2c);
#elif CONFIG_BARO == HAL_BARO_MS5611_SPI
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::spi);
#else
#error Unrecognized CONFIG_BARO setting
#endif
static AP_Baro barometer;
#if CONFIG_COMPASS == HAL_COMPASS_PX4
static AP_Compass_PX4 compass;
......
......@@ -10,7 +10,7 @@ static void init_barometer(void)
// read the barometer and return the updated altitude in meters
static void update_barometer(void)
{
barometer.read();
barometer.update();
}
......
......@@ -259,21 +259,8 @@ static GPS_Glitch gps_glitch(gps);
// flight modes convenience array
static AP_Int8 *flight_modes = &g.flight_mode1;
#if CONFIG_BARO == HAL_BARO_BMP085
static AP_Baro_BMP085 barometer;
#elif CONFIG_BARO == HAL_BARO_PX4
static AP_Baro_PX4 barometer;
#elif CONFIG_BARO == HAL_BARO_VRBRAIN
static AP_Baro_VRBRAIN barometer;
#elif CONFIG_BARO == HAL_BARO_HIL
static AP_Baro_HIL barometer;
#elif CONFIG_BARO == HAL_BARO_MS5611
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::i2c);
#elif CONFIG_BARO == HAL_BARO_MS5611_SPI
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::spi);
#else
#error Unrecognized CONFIG_BARO setting
#endif
static AP_Baro barometer;
static Baro_Glitch baro_glitch(barometer);
#if CONFIG_COMPASS == HAL_COMPASS_PX4
......@@ -462,13 +449,6 @@ static MOTOR_CLASS motors(g.rc_1, g.rc_2, g.rc_3, g.rc_4, g.single_servo_1, g.si
static MOTOR_CLASS motors(g.rc_1, g.rc_2, g.rc_3, g.rc_4);
#endif
////////////////////////////////////////////////////////////////////////////////
// PIDs
////////////////////////////////////////////////////////////////////////////////
// This is used to hold radio tuning values for in-flight CH6 tuning
float tuning_value;
////////////////////////////////////////////////////////////////////////////////
// GPS variables
////////////////////////////////////////////////////////////////////////////////
......@@ -1129,8 +1109,8 @@ static void three_hz_loop()
update_events();
if(g.radio_tuning > 0)
tuning();
// update ch6 in flight tuning
tuning();
}
// one_hz_loop - runs at 1Hz
......@@ -1353,197 +1333,5 @@ static void update_altitude()
}
}
static void tuning(){
// exit immediately when radio failsafe is invoked so tuning values are not set to zero
if (failsafe.radio || failsafe.radio_counter != 0) {
return;
}
tuning_value = (float)g.rc_6.control_in / 1000.0f;
g.rc_6.set_range(g.radio_tuning_low,g.radio_tuning_high); // 0 to 1
switch(g.radio_tuning) {
// Roll, Pitch tuning
case CH6_STABILIZE_ROLL_PITCH_KP:
g.p_stabilize_roll.kP(tuning_value);
g.p_stabilize_pitch.kP(tuning_value);
break;
case CH6_RATE_ROLL_PITCH_KP:
g.pid_rate_roll.kP(tuning_value);
g.pid_rate_pitch.kP(tuning_value);
break;
case CH6_RATE_ROLL_PITCH_KI:
g.pid_rate_roll.kI(tuning_value);
g.pid_rate_pitch.kI(tuning_value);
break;
case CH6_RATE_ROLL_PITCH_KD:
g.pid_rate_roll.kD(tuning_value);
g.pid_rate_pitch.kD(tuning_value);
break;
// Yaw tuning
case CH6_STABILIZE_YAW_KP:
g.p_stabilize_yaw.kP(tuning_value);
break;
case CH6_YAW_RATE_KP:
g.pid_rate_yaw.kP(tuning_value);
break;
case CH6_YAW_RATE_KD:
g.pid_rate_yaw.kD(tuning_value);
break;
// Altitude and throttle tuning
case CH6_ALTITUDE_HOLD_KP:
g.p_alt_hold.kP(tuning_value);
break;
case CH6_THROTTLE_RATE_KP:
g.p_throttle_rate.kP(tuning_value);
break;
case CH6_THROTTLE_ACCEL_KP:
g.pid_throttle_accel.kP(tuning_value);
break;
case CH6_THROTTLE_ACCEL_KI:
g.pid_throttle_accel.kI(tuning_value);
break;
case CH6_THROTTLE_ACCEL_KD:
g.pid_throttle_accel.kD(tuning_value);
break;
// Loiter and navigation tuning
case CH6_LOITER_POSITION_KP:
g.p_loiter_pos.kP(tuning_value);
break;
case CH6_LOITER_RATE_KP:
g.pid_loiter_rate_lon.kP(tuning_value);
g.pid_loiter_rate_lat.kP(tuning_value);
break;
case CH6_LOITER_RATE_KI:
g.pid_loiter_rate_lon.kI(tuning_value);
g.pid_loiter_rate_lat.kI(tuning_value);
break;
case CH6_LOITER_RATE_KD:
g.pid_loiter_rate_lon.kD(tuning_value);
g.pid_loiter_rate_lat.kD(tuning_value);
break;
case CH6_WP_SPEED:
// set waypoint navigation horizontal speed to 0 ~ 1000 cm/s
wp_nav.set_speed_xy(g.rc_6.control_in);
break;
// Acro roll pitch gain
case CH6_ACRO_RP_KP:
g.acro_rp_p = tuning_value;
break;
// Acro yaw gain
case CH6_ACRO_YAW_KP:
g.acro_yaw_p = tuning_value;
break;
#if FRAME_CONFIG == HELI_FRAME
case CH6_HELI_EXTERNAL_GYRO:
motors.ext_gyro_gain(g.rc_6.control_in);
break;
case CH6_RATE_PITCH_FF:
g.pid_rate_pitch.ff(tuning_value);
break;
case CH6_RATE_ROLL_FF:
g.pid_rate_roll.ff(tuning_value);
break;
case CH6_RATE_YAW_FF:
g.pid_rate_yaw.ff(tuning_value);
break;
#endif
case CH6_AHRS_YAW_KP:
ahrs._kp_yaw.set(tuning_value);
break;
case CH6_AHRS_KP:
ahrs._kp.set(tuning_value);
break;
case CH6_DECLINATION:
// set declination to +-20degrees
compass.set_declination(ToRad((2.0f * g.rc_6.control_in - g.radio_tuning_high)/100.0f), false); // 2nd parameter is false because we do not want to save to eeprom because this would have a performance impact
break;
case CH6_CIRCLE_RATE:
// set circle rate
circle_nav.set_rate(g.rc_6.control_in/25-20); // allow approximately 45 degree turn rate in either direction
break;
case CH6_SONAR_GAIN:
// set sonar gain
g.sonar_gain.set(tuning_value);
break;
#if 0
// disabled for now - we need accessor functions
case CH6_EKF_VERTICAL_POS:
// EKF's baro vs accel (higher rely on accels more, baro impact is reduced)
ahrs.get_NavEKF()._gpsVertPosNoise = tuning_value;
break;
case CH6_EKF_HORIZONTAL_POS:
// EKF's gps vs accel (higher rely on accels more, gps impact is reduced)
ahrs.get_NavEKF()._gpsHorizPosNoise = tuning_value;
break;
case CH6_EKF_ACCEL_NOISE:
// EKF's accel noise (lower means trust accels more, gps & baro less)
ahrs.get_NavEKF()._accNoise = tuning_value;
break;
#endif
case CH6_RC_FEEL_RP:
// roll-pitch input smoothing
g.rc_feel_rp = g.rc_6.control_in / 10;
break;
case CH6_RATE_PITCH_KP:
g.pid_rate_pitch.kP(tuning_value);
break;
case CH6_RATE_PITCH_KI:
g.pid_rate_pitch.kI(tuning_value);
break;
case CH6_RATE_PITCH_KD:
g.pid_rate_pitch.kD(tuning_value);
break;
case CH6_RATE_ROLL_KP:
g.pid_rate_roll.kP(tuning_value);
break;
case CH6_RATE_ROLL_KI:
g.pid_rate_roll.kI(tuning_value);
break;
case CH6_RATE_ROLL_KD:
g.pid_rate_roll.kD(tuning_value);
break;
}
}
AP_HAL_MAIN();
......@@ -194,7 +194,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
MAV_SYS_STATUS_SENSOR_3D_MAG |
MAV_SYS_STATUS_SENSOR_GPS |
MAV_SYS_STATUS_SENSOR_RC_RECEIVER);
if (barometer.healthy()) {
if (barometer.all_healthy()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
}
if (g.compass_enabled && compass.healthy(0) && ahrs.use_compass()) {
......
ArduCopter Release Notes:
------------------------------------------------------------------
ArduCopter 3.2.1-rc1 08-Jan-2014
ArduCopter 3.2.1-rc1 08-Jan-2015
Changes from 3.2
1) Enhancements:
a) reduced twitch when passing Spline waypoints
......
......@@ -5,7 +5,10 @@
*/
#ifndef DRIFT_SPEEDGAIN
# define DRIFT_SPEEDGAIN 14.0f
# define DRIFT_SPEEDGAIN 8.0f
#endif
#ifndef DRIFT_SPEEDLIMIT
# define DRIFT_SPEEDLIMIT 560.0f
#endif
#ifndef DRIFT_THR_ASSIST_GAIN
......@@ -38,6 +41,7 @@ static bool drift_init(bool ignore_checks)
static void drift_run()
{
static float breaker = 0.0;
static float roll_input = 0.0;
int16_t target_roll, target_pitch;
float target_yaw_rate;
int16_t pilot_throttle_scaled;
......@@ -63,16 +67,21 @@ static void drift_run()
float roll_vel = vel.y * ahrs.cos_yaw() - vel.x * ahrs.sin_yaw(); // body roll vel
float pitch_vel = vel.y * ahrs.sin_yaw() + vel.x * ahrs.cos_yaw(); // body pitch vel
float pitch_vel2 = min(fabs(pitch_vel), 800);
// gain sceduling for Yaw
float pitch_vel2 = min(fabs(pitch_vel), 2000);
target_yaw_rate = ((float)target_roll/1.0f) * (1.0f - (pitch_vel2 / 5000.0f)) * g.acro_yaw_p;
// simple gain scheduling for yaw input
target_yaw_rate = (float)(target_roll/2.0f) * (1.0f - (pitch_vel2 / 2400.0f)) * g.acro_yaw_p;
roll_vel = constrain_float(roll_vel, -DRIFT_SPEEDLIMIT, DRIFT_SPEEDLIMIT);
pitch_vel = constrain_float(pitch_vel, -DRIFT_SPEEDLIMIT, DRIFT_SPEEDLIMIT);
roll_input = roll_input * .96 + (float)g.rc_4.control_in * .04;
roll_vel = constrain_float(roll_vel, -322, 322);
pitch_vel = constrain_float(pitch_vel, -322, 322);
//convert user input into desired roll velocity
float roll_vel_error = roll_vel - (roll_input / DRIFT_SPEEDGAIN);
// always limit roll
target_roll = roll_vel * -DRIFT_SPEEDGAIN;
// Roll velocity is feed into roll acceleration to minimize slip
target_roll = roll_vel_error * -DRIFT_SPEEDGAIN;
target_roll = constrain_int16(target_roll, -4500, 4500);
// If we let go of sticks, bring us to a stop
if(target_pitch == 0){
......
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// counter to verify landings
static uint16_t land_detector = LAND_DETECTOR_TRIGGER; // we assume we are landed
static bool land_with_gps;
static uint32_t land_start_time;
......@@ -198,46 +196,6 @@ static float get_land_descent_speed()
}
}
// 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
// called at 50hz
static void update_land_detector()
{
// 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) {
// 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 = LAND_DETECTOR_TRIGGER;
}
}
} else {
// we've sensed movement up or down so reset land_detector
land_detector = 0;
// if throttle output is high then clear landing flag
if (motors.get_throttle_out() > get_non_takeoff_throttle()) {
set_land_complete(false);
}
}
// 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
// called during GPS failsafe to ensure that if we were already in LAND mode that we do not use the GPS
// has no effect if we are not already in LAND mode
......
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// counter to verify landings
static uint16_t land_detector = LAND_DETECTOR_TRIGGER; // we assume we are landed
// 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
// called at 50hz
static void update_land_detector()
{
bool climb_rate_low = (abs(climb_rate) < LAND_DETECTOR_CLIMBRATE_MAX) && (abs(baro_climbrate) < LAND_DETECTOR_BARO_CLIMBRATE_MAX);
bool target_climb_rate_low = !pos_control.is_active_z() || (pos_control.get_desired_velocity().z < LAND_SPEED);
bool motor_at_lower_limit = motors.limit.throttle_lower;
bool throttle_low = (FRAME_CONFIG == HELI_FRAME) || (motors.get_throttle_out() < get_non_takeoff_throttle());
bool not_rotating_fast = (ahrs.get_gyro().length() < LAND_DETECTOR_ROTATION_MAX);
if (climb_rate_low && target_climb_rate_low && motor_at_lower_limit && throttle_low && not_rotating_fast) {
if (!ap.land_complete) {
// 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 = LAND_DETECTOR_TRIGGER;
}
}
} else {
// we've sensed movement up or down so reset land_detector
land_detector = 0;
// if throttle output is high then clear landing flag
if (motors.get_throttle_out() > get_non_takeoff_throttle()) {
set_land_complete(false);
}
}
// set land maybe flag
set_land_complete_maybe(land_detector >= LAND_DETECTOR_MAYBE_TRIGGER);
}
......@@ -232,7 +232,7 @@ static void pre_arm_checks(bool display_failure)
// check Baro
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_BARO)) {
// barometer health check
if(!barometer.healthy()) {
if(!barometer.all_healthy()) {
if (display_failure) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Barometer not healthy"));
}
......
......@@ -16,7 +16,7 @@ static void init_barometer(bool full_calibration)
// return barometric altitude in centimeters
static void read_barometer(void)
{
barometer.read();
barometer.update();
if (should_log(MASK_LOG_IMU)) {
Log_Write_Baro();
}
......
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
* tuning.pde - function to update various parameters in flight using the ch6 tuning knob
* This should not be confused with the AutoTune feature which can bve found in control_autotune.pde
*/
// tuning - updates parameters based on the ch6 tuning knob's position
// should be called at 3.3hz
static void tuning() {
// exit immediately if not tuning of when radio failsafe is invoked so tuning values are not set to zero
if ((g.radio_tuning <= 0) || failsafe.radio || failsafe.radio_counter != 0) {
return;
}
float tuning_value = (float)g.rc_6.control_in / 1000.0f;
g.rc_6.set_range(g.radio_tuning_low,g.radio_tuning_high);
switch(g.radio_tuning) {
// Roll, Pitch tuning
case CH6_STABILIZE_ROLL_PITCH_KP:
g.p_stabilize_roll.kP(tuning_value);
g.p_stabilize_pitch.kP(tuning_value);
break;
case CH6_RATE_ROLL_PITCH_KP:
g.pid_rate_roll.kP(tuning_value);
g.pid_rate_pitch.kP(tuning_value);
break;
case CH6_RATE_ROLL_PITCH_KI:
g.pid_rate_roll.kI(tuning_value);
g.pid_rate_pitch.kI(tuning_value);
break;
case CH6_RATE_ROLL_PITCH_KD:
g.pid_rate_roll.kD(tuning_value);
g.pid_rate_pitch.kD(tuning_value);
break;
// Yaw tuning
case CH6_STABILIZE_YAW_KP:
g.p_stabilize_yaw.kP(tuning_value);
break;
case CH6_YAW_RATE_KP:
g.pid_rate_yaw.kP(tuning_value);
break;
case CH6_YAW_RATE_KD:
g.pid_rate_yaw.kD(tuning_value);
break;
// Altitude and throttle tuning
case CH6_ALTITUDE_HOLD_KP:
g.p_alt_hold.kP(tuning_value);
break;
case CH6_THROTTLE_RATE_KP:
g.p_throttle_rate.kP(tuning_value);
break;
case CH6_THROTTLE_ACCEL_KP:
g.pid_throttle_accel.kP(tuning_value);
break;
case CH6_THROTTLE_ACCEL_KI:
g.pid_throttle_accel.kI(tuning_value);
break;
case CH6_THROTTLE_ACCEL_KD:
g.pid_throttle_accel.kD(tuning_value);
break;
// Loiter and navigation tuning
case CH6_LOITER_POSITION_KP:
g.p_loiter_pos.kP(tuning_value);
break;
case CH6_LOITER_RATE_KP:
g.pid_loiter_rate_lon.kP(tuning_value);
g.pid_loiter_rate_lat.kP(tuning_value);
break;
case CH6_LOITER_RATE_KI:
g.pid_loiter_rate_lon.kI(tuning_value);
g.pid_loiter_rate_lat.kI(tuning_value);
break;
case CH6_LOITER_RATE_KD:
g.pid_loiter_rate_lon.kD(tuning_value);
g.pid_loiter_rate_lat.kD(tuning_value);
break;
case CH6_WP_SPEED:
// set waypoint navigation horizontal speed to 0 ~ 1000 cm/s
wp_nav.set_speed_xy(g.rc_6.control_in);
break;
// Acro roll pitch gain
case CH6_ACRO_RP_KP:
g.acro_rp_p = tuning_value;
break;
// Acro yaw gain
case CH6_ACRO_YAW_KP:
g.acro_yaw_p = tuning_value;
break;
#if FRAME_CONFIG == HELI_FRAME
case CH6_HELI_EXTERNAL_GYRO:
motors.ext_gyro_gain(g.rc_6.control_in);
break;
case CH6_RATE_PITCH_FF:
g.pid_rate_pitch.ff(tuning_value);
break;
case CH6_RATE_ROLL_FF:
g.pid_rate_roll.ff(tuning_value);
break;
case CH6_RATE_YAW_FF:
g.pid_rate_yaw.ff(tuning_value);
break;
#endif
case CH6_AHRS_YAW_KP:
ahrs._kp_yaw.set(tuning_value);
break;
case CH6_AHRS_KP:
ahrs._kp.set(tuning_value);
break;
case CH6_DECLINATION:
// set declination to +-20degrees
compass.set_declination(ToRad((2.0f * g.rc_6.control_in - g.radio_tuning_high)/100.0f), false); // 2nd parameter is false because we do not want to save to eeprom because this would have a performance impact
break;
case CH6_CIRCLE_RATE:
// set circle rate
circle_nav.set_rate(g.rc_6.control_in/25-20); // allow approximately 45 degree turn rate in either direction
break;
case CH6_SONAR_GAIN:
// set sonar gain
g.sonar_gain.set(tuning_value);
break;
#if 0
// disabled for now - we need accessor functions
case CH6_EKF_VERTICAL_POS:
// EKF's baro vs accel (higher rely on accels more, baro impact is reduced)
ahrs.get_NavEKF()._gpsVertPosNoise = tuning_value;
break;
case CH6_EKF_HORIZONTAL_POS:
// EKF's gps vs accel (higher rely on accels more, gps impact is reduced)
ahrs.get_NavEKF()._gpsHorizPosNoise = tuning_value;
break;
case CH6_EKF_ACCEL_NOISE:
// EKF's accel noise (lower means trust accels more, gps & baro less)
ahrs.get_NavEKF()._accNoise = tuning_value;
break;
#endif
case CH6_RC_FEEL_RP:
// roll-pitch input smoothing
g.rc_feel_rp = g.rc_6.control_in / 10;
break;
case CH6_RATE_PITCH_KP:
g.pid_rate_pitch.kP(tuning_value);
break;
case CH6_RATE_PITCH_KI:
g.pid_rate_pitch.kI(tuning_value);
break;
case CH6_RATE_PITCH_KD:
g.pid_rate_pitch.kD(tuning_value);
break;
case CH6_RATE_ROLL_KP:
g.pid_rate_roll.kP(tuning_value);
break;
case CH6_RATE_ROLL_KI:
g.pid_rate_roll.kI(tuning_value);
break;
case CH6_RATE_ROLL_KD:
g.pid_rate_roll.kD(tuning_value);
break;
}
}
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define THISFIRMWARE "ArduPlane V3.2.1alpha"
#define THISFIRMWARE "ArduPlane V3.2.1alpha2"
/*
Lead developer: Andrew Tridgell
......@@ -154,7 +154,6 @@ static void print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode);
////////////////////////////////////////////////////////////////////////////////
// DataFlash
////////////////////////////////////////////////////////////////////////////////
#if LOGGING_ENABLED == ENABLED
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
static DataFlash_APM1 DataFlash;
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
......@@ -165,7 +164,6 @@ static DataFlash_File DataFlash(HAL_BOARD_LOG_DIRECTORY);
// no dataflash driver
DataFlash_Empty DataFlash;
#endif
#endif
// has a log download started?
static bool in_log_download;
......@@ -193,21 +191,7 @@ static AP_GPS gps;
// flight modes convenience array
static AP_Int8 *flight_modes = &g.flight_mode1;
#if CONFIG_BARO == HAL_BARO_BMP085
static AP_Baro_BMP085 barometer;
#elif CONFIG_BARO == HAL_BARO_PX4
static AP_Baro_PX4 barometer;
#elif CONFIG_BARO == HAL_BARO_VRBRAIN
static AP_Baro_VRBRAIN barometer;
#elif CONFIG_BARO == HAL_BARO_HIL
static AP_Baro_HIL barometer;
#elif CONFIG_BARO == HAL_BARO_MS5611
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::i2c);
#elif CONFIG_BARO == HAL_BARO_MS5611_SPI
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::spi);
#else
#error Unrecognized CONFIG_BARO setting
#endif
static AP_Baro barometer;
#if CONFIG_COMPASS == HAL_COMPASS_PX4
static AP_Compass_PX4 compass;
......@@ -1511,7 +1495,7 @@ static void set_flight_stage(AP_SpdHgtControl::FlightStage fs)
static void update_alt()
{
barometer.read();
barometer.update();
if (should_log(MASK_LOG_IMU)) {
Log_Write_Baro();
}
......
......@@ -229,7 +229,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
control_sensors_health &= ~MAV_SYS_STATUS_AHRS;
}
if (barometer.healthy()) {
if (barometer.all_healthy()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
}
if (g.compass_enabled && compass.healthy(0) && ahrs.use_compass()) {
......@@ -1084,7 +1084,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// run pre_arm_checks and arm_checks and display failures
if (arming.arm(AP_Arming::MAVLINK)) {
//only log if arming was successful
channel_throttle->enable_out();
channel_throttle->enable_out();
Log_Arm_Disarm();
result = MAV_RESULT_ACCEPTED;
} else {
......
......@@ -654,9 +654,11 @@ static void Log_Write_IMU() {}
static void Log_Write_RC() {}
static void Log_Write_Airspeed(void) {}
static void Log_Write_Baro(void) {}
static void Log_Write_Sonar() {}
#if OPTFLOW == ENABLED
static void Log_Write_Optflow() {}
#endif
static void Log_Arm_Disarm() {}
static int8_t process_logs(uint8_t argc, const Menu::arg *argv) {
return 0;
......
......@@ -672,7 +672,9 @@ static bool should_log(uint32_t mask)
// we have to set in_mavlink_delay to prevent logging while
// writing headers
in_mavlink_delay = true;
#if LOGGING_ENABLED == ENABLED
start_logging();
#endif
in_mavlink_delay = false;
}
return ret;
......
......@@ -577,7 +577,7 @@ test_pressure(uint8_t argc, const Menu::arg *argv)
while(1) {
hal.scheduler->delay(100);
barometer.read();
barometer.update();
if (!barometer.healthy()) {
cliSerial->println_P(PSTR("not healthy"));
......
......@@ -20,7 +20,7 @@
/* the pin header uses */
// "P9.27", /* pru0: pr1_pru0_pru_r30_5 */
"P8.15", /* pru0: pr1_pru0_pru_r30_15 */
"P8.15", /* pru0: pr1_pru0_pru_r30_15, PPM-sum, SBUS, DSM */
// "P8.12", /* pru0: pr1_pru0_pru_r30_14 */
// "P9.25", /* pru0: pr1_pru0_pru_r30_7 */
// "P9.41", /* pru0: pr1_pru0_pru_r30_6 */
......@@ -39,18 +39,18 @@
//"P8.20", /* pru1: pr1_pru1_pru_r30_13 */
//"P8.21", /* pru1: pr1_pru1_pru_r30_12 */
"P8.27", /* pru1: pr1_pru1_pru_r30_8 */
"P8.28", /* pru1: pr1_pru1_pru_r30_10 */
"P8.29", /* pru1: pr1_pru1_pru_r30_9 */
"P8.30", /* pru1: pr1_pru1_pru_r30_11 */
"P8.39", /* pru1: pr1_pru1_pru_r30_6 */
"P8.40", /* pru1: pr1_pru1_pru_r30_7 */
"P8.41", /* pru1: pr1_pru1_pru_r30_4 */
"P8.42", /* pru1: pr1_pru1_pru_r30_5 */
"P8.43", /* pru1: pr1_pru1_pru_r30_2 */
"P8.44", /* pru1: pr1_pru1_pru_r30_3 */
"P8.45", /* pru1: pr1_pru1_pru_r30_0 */
"P8.46", /* pru1: pr1_pru1_pru_r30_1 */
"P8.27", /* pru1: pr1_pru1_pru_r30_8, CH_2 */
"P8.28", /* pru1: pr1_pru1_pru_r30_10, CH_1 */
"P8.29", /* pru1: pr1_pru1_pru_r30_9, CH_4 */
"P8.30", /* pru1: pr1_pru1_pru_r30_11, CH_3 */
"P8.39", /* pru1: pr1_pru1_pru_r30_6, CH_6 */
"P8.40", /* pru1: pr1_pru1_pru_r30_7, CH_5 */
"P8.41", /* pru1: pr1_pru1_pru_r30_4, CH_8 */
"P8.42", /* pru1: pr1_pru1_pru_r30_5, CH_7 */
"P8.43", /* pru1: pr1_pru1_pru_r30_2, CH_10 */
"P8.44", /* pru1: pr1_pru1_pru_r30_3, CH_9 */
"P8.45", /* pru1: pr1_pru1_pru_r30_0, CH_12 */
"P8.46", /* pru1: pr1_pru1_pru_r30_1, CH_11 */
/* pru1: pr1_pru1_pru_r30_14 is on UART0_RXD */
/* pru1: pr1_pru1_pru_r30_15 is on UART0_TXD */
/* the hardware IP uses */
......@@ -70,7 +70,7 @@
pru_pru_pins: pinmux_pru_pru_pins {
pinctrl-single,pins = <
// 0x1a4 0x25 /* mcasp0_fsr.pr1_pru0_pru_r30_5, MODE5 | OUTPUT | PRU */
0x03c 0x2E /* gpmc_ad13.pr1_pru0_pru_r30_15, MODE6 | INPUT | PRU */
0x03c 0x2E /* gpmc_ad13.pr1_pru0_pru_r30_15, MODE6 | INPUT | PRU, PPM-sum, SBUS, DSM */
// 0x030 0x26 /* gpmc_ad12.pr1_pru0_pru_r30_14, MODE6 | OUTPUT | PRU */
// 0x1ac 0x25 /* mcasp0_ahclkx.pr1_pru0_pru_r30_7, MODE5 | OUTPUT | PRU */
// 0x1a8 0x25 /* mcasp0_axr1.pr1_pru0_pru_r30_6, MODE5 | OUTPUT | PRU */
......@@ -82,18 +82,18 @@
//0x084 0x25 /* gpmc_csn2.pr1_pru1_pru_r30_13, MODE5 | OUTPUT | PRU */
//0x080 0x25 /* gpmc_csn1.pr1_pru1_pru_r30_12, MODE5 | OUTPUT | PRU */
0x0e0 0x25 /* lcd_vsync.pr1_pru1_pru_r30_8, MODE5 | OUTPUT | PRU */
0x0e8 0x25 /* lcd_pclk.pr1_pru1_pru_r30_10, MODE5 | OUTPUT | PRU */
0x0e4 0x25 /* lcd_hsync.pr1_pru1_pru_r30_9, MODE5 | OUTPUT | PRU */
0x0ec 0x25 /* lcd_ac_bias_en.pr1_pru1_pru_r30_11, MODE5 | OUTPUT | PRU */
0x0b8 0x25 /* pr1_pru1_pru_r30_6, MODE5 | OUTPUT | PRU */
0x0bc 0x25 /* lcd_data7.pr1_pru1_pru_r30_7, MODE5 | OUTPUT | PRU */
0x0b0 0x25 /* lcd_data4.pr1_pru1_pru_r30_4, MODE5 | OUTPUT | PRU */
0x0b4 0x25 /* lcd_data5.pr1_pru1_pru_r30_5, MODE5 | OUTPUT | PRU */
0x0a8 0x25 /* pr1_pru1_pru_r31_2, MODE5 | OUTPUT | PRU */
0x0ac 0x25 /* lcd_data3.pr1_pru1_pru_r30_3, MODE5 | OUTPUT | PRU */
0x0a0 0x25 /* lcd_data0.pr1_pru1_pru_r30_0, MODE5 | OUTPUT | PRU */
0x0a4 0x25 /* lcd_data1.pr1_pru1_pru_r30_1, MODE5 | OUTPUT | PRU */
0x0e0 0x25 /* lcd_vsync.pr1_pru1_pru_r30_8, MODE5 | OUTPUT | PRU, CH_2 */
0x0e8 0x25 /* lcd_pclk.pr1_pru1_pru_r30_10, MODE5 | OUTPUT | PRU, CH_1 */
0x0e4 0x25 /* lcd_hsync.pr1_pru1_pru_r30_9, MODE5 | OUTPUT | PRU, CH_4 */
0x0ec 0x25 /* lcd_ac_bias_en.pr1_pru1_pru_r30_11, MODE5 | OUTPUT | PRU, CH_3 */
0x0b8 0x25 /* lcd_data6.pr1_pru1_pru_r30_6, MODE5 | OUTPUT | PRU, CH_6 */
0x0bc 0x25 /* lcd_data7.pr1_pru1_pru_r30_7, MODE5 | OUTPUT | PRU, CH_5 */
0x0b0 0x25 /* lcd_data4.pr1_pru1_pru_r30_4, MODE5 | OUTPUT | PRU, CH_8 */
0x0b4 0x25 /* lcd_data5.pr1_pru1_pru_r30_5, MODE5 | OUTPUT | PRU, CH_7 */
0x0a8 0x25 /* lcd_data2.pr1_pru1_pru_r30_2, MODE5 | OUTPUT | PRU, CH_10 */
0x0ac 0x25 /* lcd_data3.pr1_pru1_pru_r30_3, MODE5 | OUTPUT | PRU, CH_9 */
0x0a0 0x25 /* lcd_data0.pr1_pru1_pru_r30_0, MODE5 | OUTPUT | PRU, CH_12 */
0x0a4 0x25 /* lcd_data1.pr1_pru1_pru_r30_1, MODE5 | OUTPUT | PRU, CH_11 */
>;
};
};
......
......@@ -18,22 +18,24 @@
/* state the resources this cape uses */
exclusive-use =
/* the pin header uses */
/* PRU */
/* PRU RCInput */
"P8.11", /* pru0: pr1_pru0_pru_r30_15 */
"P8.15", /* pru0: pr1_pru0_pru_r31_15*/
"P8.15", /* pru0: pr1_pru0_pru_r31_15, PPM-sum, SBUS, DSM */
"P8.27", /* pru1: pr1_pru1_pru_r30_8 */
"P8.28", /* pru1: pr1_pru1_pru_r30_10 */
"P8.29", /* pru1: pr1_pru1_pru_r30_9 */
"P8.30", /* pru1: pr1_pru1_pru_r30_11 */
"P8.39", /* pru1: pr1_pru1_pru_r30_6 */
"P8.40", /* pru1: pr1_pru1_pru_r30_7 */
"P8.41", /* pru1: pr1_pru1_pru_r30_4 */
"P8.42", /* pru1: pr1_pru1_pru_r30_5 */
"P8.43", /* pru1: pr1_pru1_pru_r30_2 */
"P8.44", /* pru1: pr1_pru1_pru_r30_3 */
"P8.45", /* pru1: pr1_pru1_pru_r30_0 */
"P8.46", /* pru1: pr1_pru1_pru_r30_1 */
/* PRU RCOutput */
"P8.27", /* pru1: pr1_pru1_pru_r30_8, CH_2 */
"P8.28", /* pru1: pr1_pru1_pru_r30_10, CH_1 */
"P8.29", /* pru1: pr1_pru1_pru_r30_9, CH_4 */
"P8.30", /* pru1: pr1_pru1_pru_r30_11, CH_3 */
"P8.39", /* pru1: pr1_pru1_pru_r30_6, CH_6 */
"P8.40", /* pru1: pr1_pru1_pru_r30_7, CH_5 */
"P8.41", /* pru1: pr1_pru1_pru_r30_4, CH_8 */
"P8.42", /* pru1: pr1_pru1_pru_r30_5, CH_7 */
"P8.43", /* pru1: pr1_pru1_pru_r30_2, CH_10 */
"P8.44", /* pru1: pr1_pru1_pru_r30_3, CH_9 */
"P8.45", /* pru1: pr1_pru1_pru_r30_0, CH_12 */
"P8.46", /* pru1: pr1_pru1_pru_r30_1, CH_11 */
/* SPI0 */
"P9.22", /* SPI0_SCLK */
......@@ -74,20 +76,20 @@
pru_pru_pins: pinmux_pru_pru_pins {
pinctrl-single,pins = <
0x034 0x26 /* gpmc_ad13.pr1_pru0_pru_r30_15, MODE6 | OUTPUT | PRU */
0x03c 0x2e /* gpmc_ad15.pr1_pru0_pru_r30_15, MODE 6 | INPUT | PRU */
0x0e0 0x25 /* lcd_vsync.pr1_pru1_pru_r30_8, MODE5 | OUTPUT | PRU */
0x0e8 0x25 /* lcd_pclk.pr1_pru1_pru_r30_10, MODE5 | OUTPUT | PRU */
0x0e4 0x25 /* lcd_hsync.pr1_pru1_pru_r30_9, MODE5 | OUTPUT | PRU */
0x0ec 0x25 /* lcd_ac_bias_en.pr1_pru1_pru_r30_11, MODE5 | OUTPUT | PRU */
0x0b8 0x25 /* pr1_pru1_pru_r30_6, MODE5 | OUTPUT | PRU */
0x0bc 0x25 /* lcd_data7.pr1_pru1_pru_r30_7, MODE5 | OUTPUT | PRU */
0x0b0 0x25 /* lcd_data4.pr1_pru1_pru_r30_4, MODE5 | OUTPUT | PRU */
0x0b4 0x25 /* lcd_data5.pr1_pru1_pru_r30_5, MODE5 | OUTPUT | PRU */
0x0a8 0x25 /* pr1_pru1_pru_r31_2, MODE5 | OUTPUT | PRU */
0x0ac 0x25 /* lcd_data3.pr1_pru1_pru_r30_3, MODE5 | OUTPUT | PRU */
0x0a0 0x25 /* lcd_data0.pr1_pru1_pru_r30_0, MODE5 | OUTPUT | PRU */
0x0a4 0x25 /* lcd_data1.pr1_pru1_pru_r30_1, MODE5 | OUTPUT | PRU */
0x03c 0x2e /* gpmc_ad15.pr1_pru0_pru_r31_15, MODE6 | INPUT | PRU, PPM-sum, SBUS, DSM */
0x0e0 0x25 /* lcd_vsync.pr1_pru1_pru_r30_8, MODE5 | OUTPUT | PRU, CH_2 */
0x0e8 0x25 /* lcd_pclk.pr1_pru1_pru_r30_10, MODE5 | OUTPUT | PRU, CH_1 */
0x0e4 0x25 /* lcd_hsync.pr1_pru1_pru_r30_9, MODE5 | OUTPUT | PRU, CH_4 */
0x0ec 0x25 /* lcd_ac_bias_en.pr1_pru1_pru_r30_11, MODE5 | OUTPUT | PRU, CH_3 */
0x0b8 0x25 /* lcd_data6.pr1_pru1_pru_r30_6, MODE5 | OUTPUT | PRU, CH_6 */
0x0bc 0x25 /* lcd_data7.pr1_pru1_pru_r30_7, MODE5 | OUTPUT | PRU, CH_5 */
0x0b0 0x25 /* lcd_data4.pr1_pru1_pru_r30_4, MODE5 | OUTPUT | PRU, CH_8 */
0x0b4 0x25 /* lcd_data5.pr1_pru1_pru_r30_5, MODE5 | OUTPUT | PRU, CH_7 */
0x0a8 0x25 /* lcd_data2.pr1_pru1_pru_r30_2, MODE5 | OUTPUT | PRU, CH_10 */
0x0ac 0x25 /* lcd_data3.pr1_pru1_pru_r30_3, MODE5 | OUTPUT | PRU, CH_9 */
0x0a0 0x25 /* lcd_data0.pr1_pru1_pru_r30_0, MODE5 | OUTPUT | PRU, CH_12 */
0x0a4 0x25 /* lcd_data1.pr1_pru1_pru_r30_1, MODE5 | OUTPUT | PRU, CH_11 */
>;
};
spi0_pins_s0: spi0_pins_s0 {
......