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 (8)
......@@ -449,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
////////////////////////////////////////////////////////////////////////////////
......@@ -1116,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
......@@ -1340,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();
......@@ -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 -*-
/*
* 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;
}
}
......@@ -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;
......
......@@ -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;
......
......@@ -16,6 +16,8 @@ for b in all apm2 sitl linux; do
make clean
make $b -j4
done
make clean
make apm1-nologging
popd
for d in ArduCopter APMrover2 ArduPlane AntennaTracker; do
......
......@@ -325,7 +325,6 @@ void AC_PosControl::rate_to_accel_z()
// Reset Filter
_vel_error.z = 0;
_vel_error_filter.reset(0);
desired_accel = 0;
_flags.reset_rate_to_accel_z = false;
} else {
// calculate rate error and filter with cut off frequency of 2 Hz
......
......@@ -72,7 +72,7 @@ void loop()
(int)gps.ground_course_cd() / 100,
gps.num_sats(),
gps.time_week(),
gps.time_week_ms(),
(unsigned long)gps.time_week_ms(),
gps.status());
}
hal.scheduler->delay(10);
......
......@@ -16,6 +16,12 @@ include $(MK_DIR)/configure.mk
else
# short-circuit build for the help target
ifeq ($(MAKECMDGOALS),help)
include $(MK_DIR)/help.mk
else
# common makefile components
include $(MK_DIR)/targets.mk
include $(MK_DIR)/sketch_sources.mk
......@@ -53,3 +59,5 @@ endif
endif
endif
endif
help:
@echo ""
@echo " ArduPilot Building"
@echo " =================="
@echo ""
@echo " The following web page has detailed information on building the code"
@echo " http://dev.ardupilot.com/wiki/building-the-code/"
@echo ""
@echo " Before building a target you need to be in the target vehicle type directory"
@echo " e.g. ArduPlane, ArduCopter, APMrover2, AntennaTracker"
@echo " and run \"make configure\""
@echo ""
@echo " Most targets support a \"-upload\" extension to upload the firmware"
@echo " to a connected board. e.g. \"make px4-v2-upload\""
@echo ""
@echo " Note that the px4 builds are NOT parallel safe, NO -j flag"
@echo ""
@echo " Targets"
@echo " -------"
@echo ""
@echo " configure - Set up build for vehicle type"
@echo ""
@echo " all - Build all targets"
@echo ""
@echo " apm1 - the APM1 board"
@echo " apm2 - the APM2 board"
@echo " px4-v1 - the PX4v1 board"
@echo " px4-v2 - the Pixhawk"
@echo " pxf - the Beagle Bone Black (BBB) + PXF cape combination"
@echo " navio - the RaspberryPi + NavIO cape combination"
@echo " linux - a generic Linux build"
@echo " flymaple - the FlyMaple board"
@echo " vrbrain - the VRBrain boards"
@echo " stil - the SITL Software In The Loop simulation"
@echo " bbbmini - the Beagle Bone Black mini"
......@@ -60,8 +60,11 @@ empty: all
# cope with OBC targets
%-obc: EXTRAFLAGS += "-DOBC_FAILSAFE=ENABLED "
# cope with -nologging
%-nologging: EXTRAFLAGS += "-DLOGGING_ENABLED=DISABLED "
# cope with copter and hil targets
FRAMES = quad tri hexa y6 octa octa-quad heli single obc
FRAMES = quad tri hexa y6 octa octa-quad heli single obc nologging
BOARDS = apm1 apm2 apm2beta apm1-1280 px4 px4-v1 px4-v2 sitl flymaple linux vrbrain vrbrain-v40 vrbrain-v45 vrbrainv-50 vrbrain-v51 vrubrain-v51 vrhero-v10 erle pxf navio bbbmini
define frame_template
......