Skip to content
Permalink

Comparing changes

Choose two branches to see what’s changed or to start a new pull request. If you need to, you can also or learn more about diff comparisons.

Open a pull request

Create a new pull request by comparing changes across two branches. If you need to, you can also . Learn more about diff comparisons here.
base repository: 3drobotics/ardupilot-solo
Failed to load repositories. Confirm that selected base ref is valid, then try again.
Loading
base: solo-0.0.28
Choose a base ref
...
head repository: 3drobotics/ardupilot-solo
Failed to load repositories. Confirm that selected head ref is valid, then try again.
Loading
compare: master
Choose a head ref

Commits on Mar 3, 2015

  1. Copy the full SHA
    5b0bd49 View commit details
  2. Copy the full SHA
    3e8563d View commit details
  3. Copy the full SHA
    83e3e2f View commit details
  4. Copy the full SHA
    f6523c0 View commit details
  5. Copy the full SHA
    1217ab9 View commit details
  6. Copy the full SHA
    8eedb2c View commit details
  7. Motors: over current throttle limiting

    lthall authored and rmackay9 committed Mar 3, 2015
    Copy the full SHA
    1d0ee68 View commit details
  8. Motors: minor comment fixes

    lthall authored and rmackay9 committed Mar 3, 2015
    Copy the full SHA
    ec9d7dd View commit details
  9. Copy the full SHA
    77d4b3a View commit details
  10. Copy the full SHA
    7ab76db View commit details
  11. Copy the full SHA
    bae424f View commit details
  12. Copy the full SHA
    80b498f View commit details
  13. Motors: move thrust curve and volt scaling to parent

    Moving from MotorsMatrix to Motors allows it to be used from other frames
    lthall authored and rmackay9 committed Mar 3, 2015
    Copy the full SHA
    751dbb7 View commit details
  14. Copy the full SHA
    2eaa4a8 View commit details
  15. Copy the full SHA
    5fb3de4 View commit details
  16. Copy the full SHA
    c549b58 View commit details
  17. Motors: move batt voltage lift_max calcs to parent

    Moving from MotorsMatrix to parent Motors class allows them to be used
    by other frame types
    Also added sanity check of batt_voltage_min
    lthall authored and rmackay9 committed Mar 3, 2015
    Copy the full SHA
    6b7bdf6 View commit details
  18. Copy the full SHA
    1a9d312 View commit details
  19. Copy the full SHA
    812473f View commit details
  20. Motors: move over current throttle limiting to parent

    Moving from MotorsMatrix to parent Motors class allows this to be used
    from other frame types
    lthall authored and rmackay9 committed Mar 3, 2015
    Copy the full SHA
    529c6fe View commit details
  21. Copy the full SHA
    c711179 View commit details
  22. Copy the full SHA
    4b78b2c View commit details
  23. Copy the full SHA
    09d7cdb View commit details
  24. Motors: move battery resistance calcs to parent

    Moving from MotorsMatrix to parent Motors class allows these to be used
    from other frame types
    Also initialise battery resistance
    lthall authored and rmackay9 committed Mar 3, 2015
    Copy the full SHA
    997c6f0 View commit details
  25. Motors: add get_voltage_comp_gain

    This clarifies that lift_max is the inverse of the battery voltage gain
    compensation
    lthall authored and rmackay9 committed Mar 3, 2015
    Copy the full SHA
    3e960df View commit details
  26. Copy the full SHA
    cf8c211 View commit details
  27. Copy the full SHA
    f5f7cd5 View commit details
  28. Rover: Fix for a minor sonar problem

    Marco Walther authored and tridge committed Mar 3, 2015
    Copy the full SHA
    8629637 View commit details
  29. Rover: Fix the yellow binking lights after the AP_Notify updates

    Marco Walther authored and tridge committed Mar 3, 2015
    Copy the full SHA
    339dac1 View commit details

Commits on Mar 4, 2015

  1. Copy the full SHA
    e0f828f View commit details
  2. Copy the full SHA
    eeacbe5 View commit details
  3. Copy the full SHA
    79be500 View commit details
  4. Copy the full SHA
    58c92b0 View commit details
  5. HAL_PX4: split IO thread into separate IO and storage threads

    this prevents a blocked microSD card from blocking IO to the FRAM,
    causing parameter changes not to be sticky
    tridge committed Mar 4, 2015
    Copy the full SHA
    086f878 View commit details
  6. Copy the full SHA
    2aae594 View commit details

Commits on Mar 5, 2015

  1. Vagrant: bash gets confused if you pass in .sh files from windows

    This change prevents git from adding carriage returns to .sh files
    geeksville authored and tridge committed Mar 5, 2015
    Copy the full SHA
    76f1088 View commit details
  2. PX4: update FMUv2 bootloader

    this one adds the CHIP command so we can differentiate rev3 silicon
    tridge committed Mar 5, 2015
    Copy the full SHA
    644d0c2 View commit details

Commits on Mar 6, 2015

  1. Copy the full SHA
    517448e View commit details
  2. AC_HELI_PID: add input filter and restructure

    Also removed unused initial_ff from construtor
    lthall authored and rmackay9 committed Mar 6, 2015
    Copy the full SHA
    046949e View commit details
  3. AC_PI_2D: 2-axis PI controller

    lthall authored and rmackay9 committed Mar 6, 2015
    Copy the full SHA
    34a5bc8 View commit details
  4. Motors: add accessors for motor logging

    accessor include get_roll, get_pitch, get_yaw, throttle input
    lthall authored and rmackay9 committed Mar 6, 2015
    Copy the full SHA
    11a1980 View commit details
  5. Copter: add AUTOTUNE_AXES bitmask parameter

    This is used to allow tuning just some axis
    lthall authored and rmackay9 committed Mar 6, 2015
    Copy the full SHA
    864168e View commit details
  6. Copter: add AUTOTUNE_AGGR parameter

    lthall authored and rmackay9 committed Mar 6, 2015
    Copy the full SHA
    a9a6e88 View commit details
  7. Copter: Autotune rewrite

    Includes the following:
    Increase Autotune Limits
    Low Rate_P_Max prevents correct Rate_D prediction.
    make adjustment proportional
    increase the maximum value of Rate_P
    adjustment for zero overshoot
    Speed up autotune
    Reduce D bounce back requirement
    adapt matthewlloyd's switching
    Includes many enhancements to the basic code but doesn't bring in his
    speed up ideas
    Reduce Stab P down
    Add Calibration
    Repeat side to increase speed
    Update Autotune PI ratios
    fixup comments
    autotune incorporate aggressiveness parameter
    sets max accel for roll, pitch, yaw
    Update accel calc and set Yaw D to zero
    Calculate Accel correctly on SP Limit
    Send saved gains msg to GCS
    updates PID filter
    increase accel backoff
    save max accel if rate feedfwd enabled
    keep stabilizing
    lthall authored and rmackay9 committed Mar 6, 2015
    Copy the full SHA
    1ebf2c4 View commit details
  8. Copy the full SHA
    8ba195a View commit details
  9. Copy the full SHA
    d233ca3 View commit details
  10. Copter: integrate PID input filter

    lthall authored and rmackay9 committed Mar 6, 2015
    Copy the full SHA
    2b0fb45 View commit details
  11. Copter: ch6 tuning of yaw rate filter

    lthall authored and rmackay9 committed Mar 6, 2015
    Copy the full SHA
    1ec5eed View commit details
  12. Copter: move LOITER_RATE to 2-axis PI controller

    Also rename LOITER_RATE to VEL_XY for parameters, definitions, variables
    lthall authored and rmackay9 committed Mar 6, 2015
    Copy the full SHA
    e232867 View commit details
  13. Copter: rename loiter_pos to pos_xy

    Also renamed throttle_rate to vel_z, throttle_accel to accel_z
    lthall authored and rmackay9 committed Mar 6, 2015
    Copy the full SHA
    c78480e View commit details
Showing 850 changed files with 49,180 additions and 15,876 deletions.
6 changes: 6 additions & 0 deletions .gitattributes
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@

# bash gets confused if you pass in .sh files from windows
# This breaks Vagrant for some users.
*.sh text eol=lf


2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -54,6 +54,7 @@ ArduCopter/Debug/
ArduCopter/terrain/*.DAT
ArduCopter/test.ArduCopter/
ArduCopter/test/*
ArduPlane/test/*
ArduPlane/terrain/*.DAT
ArduPlane/test.ArduPlane/
APMrover2/test.APMrover2/
@@ -80,3 +81,4 @@ status.txt
tags
test.ArduCopter/*
Thumbs.db
!mk/PX4/ROMFS/firmware/*.bin
65 changes: 53 additions & 12 deletions .travis.yml
Original file line number Diff line number Diff line change
@@ -1,15 +1,56 @@
language: cpp

sudo: false
addons:
apt:
sources:
- ubuntu-toolchain-r-test
- george-edison55-precise-backports
packages:
- build-essential
- gawk
- ccache
- genromfs
- libc6-i386
- python-pip
- python-dev
- zlib1g-dev
- gcc-4.9
- g++-4.9
- cmake
- cmake-data
cache:
ccache: true
directories:
- $HOME/opt
before_install:
- APMDIR=$(pwd) && pushd .. && $APMDIR/Tools/scripts/install-travis-env.sh -y && . ~/.profile && popd

script:
- Tools/scripts/build_all_travis.sh

- Tools/scripts/configure-ci.sh
script:
- pushd ..
- git clone https://github.com/3drobotics/PX4Firmware-solo.git
- mv ./PX4Firmware-solo ./PX4Firmware
- git clone https://github.com/3drobotics/PX4NuttX.git
- popd
- . ~/.profile
- pushd ArduCopter
- make configure
- make px4-v2
before_cache:
- ccache -z
compiler:
- gcc
deploy:
provider: releases
api_key:
secure: S3M/mXvbc5OcJsqhKmbMa9pvjJ8P/wph9iEFU/nVVCl/yCIW4nzyftK9UcHaCGJDLxdrKWGOZhwd+gTQNcFtTh8pHd5kXwqeF33//qlumHp4k1LPQFSmYea0yKHl3pTejeVxjS4yJ9lms3dIwLL+io/owKjMJY2j/4WGeo6UK7T5M2vn4tY+7A9IeA3DG3l36OsLGBCOAj/kObmNE8ru7lWQWl7EBIqn1EKwqU/TBWL4Z018uADB0GRAmoCHHMtB5dIj93tuS3fOD3dpEOH/cIjNN8AQ2/OK8qVNv+NZuxtjNECX6hMW22UXcJVSGIE5iTqpx2RQWEiQjTu8w6OIe6IauwTO1HCBzTBC2jrHkTEfTRs0jm/JJbjywCa0mZMxaSxf6BRuf3BgIIwes2Xw00eK9UtFvuevsYN6WJuXmYf83zRxZwPW6tChK4lDv9BDb2YMWu7OE0KOZQG7U2dNJxxnCkXl4xVmRC3yPpjtng5gIiIszpHSqa68pMNA+lwBpc9eDngKaRnyeRlEc0qXHn7o6JJmYxrBdNJJbxZqzhUazDo/xicOeEYiKLjuWtVUzuXyQRQMlWPKYExuoQadEmj7IpTqN4PPoWL7Moe5eozBwnMa4aROZQTLxDzl8y7M0L4eIZX/FwiXXisiO39D8eTnziGF20njYKr7KO5A8wQ=
file: 'ArduCopter-v2.px4'
skip_cleanup: true
on:
tags: true
all_branches: true
notifications:
webhooks:
urls:
- https://webhooks.gitter.im/e/e5e0b55e353e53945b4b
on_success: change # options: [always|never|change] default: always
on_failure: always # options: [always|never|change] default: always
on_start: false # default: false
slack:
rooms:
- 3dr:tT1PqGCjL6mimPYss3XRrVL7
on_failure: change
on_success: change

36 changes: 13 additions & 23 deletions APMrover2/APMrover2.pde
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#define THISFIRMWARE "ArduRover v2.48"
#define THISFIRMWARE "ArduRover v2.49"
/*
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
@@ -204,29 +204,21 @@ static AP_Int8 *modes = &g.mode1;

static AP_Baro barometer;

#if CONFIG_COMPASS == HAL_COMPASS_PX4
static AP_Compass_PX4 compass;
#elif CONFIG_COMPASS == HAL_COMPASS_VRBRAIN
static AP_Compass_VRBRAIN compass;
#elif CONFIG_COMPASS == HAL_COMPASS_HMC5843
static AP_Compass_HMC5843 compass;
#elif CONFIG_COMPASS == HAL_COMPASS_HIL
static AP_Compass_HIL compass;
#elif CONFIG_COMPASS == HAL_COMPASS_AK8963
static AP_Compass_AK8963_MPU9250 compass;
#else
#error Unrecognized CONFIG_COMPASS setting
#endif
Compass compass;

#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
AP_ADC_ADS7844 apm1_adc;
#endif

AP_InertialSensor ins;

////////////////////////////////////////////////////////////////////////////////
// SONAR
static RangeFinder sonar;

// Inertial Navigation EKF
#if AP_AHRS_NAVEKF_AVAILABLE
AP_AHRS_NavEKF ahrs(ins, barometer, gps);
AP_AHRS_NavEKF ahrs(ins, barometer, gps, sonar);
#else
AP_AHRS_DCM ahrs(ins, barometer, gps);
#endif
@@ -265,10 +257,6 @@ static GCS_MAVLINK gcs[MAVLINK_COMM_NUM_BUFFERS];
// is to take the 0 to 1024 range down to an 8 bit range for MAVLink
AP_HAL::AnalogSource *rssi_analog_source;

////////////////////////////////////////////////////////////////////////////////
// SONAR
static RangeFinder sonar;

// relay support
AP_Relay relay;

@@ -523,7 +511,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
{ update_notify, 1, 300 },
{ one_second_loop, 50, 3000 },
#if FRSKY_TELEM_ENABLED == ENABLED
{ telemetry_send, 10, 100 }
{ frsky_telemetry_send, 10, 100 }
#endif
};

@@ -537,17 +525,17 @@ void setup() {
// load the default values of variables listed in var_info[]
AP_Param::setup_sketch_defaults();

notify.init(false);

// rover does not use arming nor pre-arm checks
AP_Notify::flags.armed = true;
AP_Notify::flags.pre_arm_check = true;
AP_Notify::flags.pre_arm_gps_check = true;
AP_Notify::flags.failsafe_battery = false;

notify.init(false);

rssi_analog_source = hal.analogin->channel(ANALOG_INPUT_NONE);

init_ardupilot();
init_ardupilot();

// initialise the main loop scheduler
scheduler.init(&scheduler_tasks[0], sizeof(scheduler_tasks)/sizeof(scheduler_tasks[0]));
@@ -749,6 +737,8 @@ static void one_second_loop(void)
}
counter = 0;
}

ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
}

static void update_GPS_50Hz(void)
99 changes: 79 additions & 20 deletions APMrover2/GCS_Mavlink.pde
Original file line number Diff line number Diff line change
@@ -177,11 +177,17 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
int16_t battery_current = -1;
int8_t battery_remaining = -1;

if (battery.has_current()) {
if (battery.has_current() && battery.healthy()) {
battery_remaining = battery.capacity_remaining_pct();
battery_current = battery.current_amps() * 100;
}

if (AP_Notify::flags.initialising) {
// while initialising the gyros and accels are not enabled
control_sensors_enabled &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
control_sensors_health &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
}

mavlink_msg_sys_status_send(
chan,
control_sensors_present,
@@ -321,29 +327,37 @@ static void NOINLINE send_hwstatus(mavlink_channel_t chan)

static void NOINLINE send_rangefinder(mavlink_channel_t chan)
{
if (!sonar.healthy()) {
if (!sonar.has_data(0) && !sonar.has_data(1)) {
// no sonar to report
return;
}

float distance_cm = 0.0f;
float voltage = 0.0f;

/*
report smaller distance of two sonars if more than one enabled
report smaller distance of two sonars
*/
float distance_cm, voltage;
if (!sonar.healthy(1)) {
distance_cm = sonar.distance_cm(0);
voltage = sonar.voltage_mv(0) * 0.001f;
if (sonar.has_data(0) && sonar.has_data(1)) {
if (sonar.distance_cm(0) <= sonar.distance_cm(1)) {
distance_cm = sonar.distance_cm(0);
voltage = sonar.voltage_mv(0);
} else {
distance_cm = sonar.distance_cm(1);
voltage = sonar.voltage_mv(1);
}
} else {
float dist1 = sonar.distance_cm(0);
float dist2 = sonar.distance_cm(1);
if (dist1 <= dist2) {
distance_cm = dist1;
// only sonar 0 or sonar 1 has data
if (sonar.has_data(0)) {
distance_cm = sonar.distance_cm(0);
voltage = sonar.voltage_mv(0) * 0.001f;
} else {
distance_cm = dist2;
}
if (sonar.has_data(1)) {
distance_cm = sonar.distance_cm(1);
voltage = sonar.voltage_mv(1) * 0.001f;
}
}

mavlink_msg_rangefinder_send(
chan,
distance_cm * 0.01f,
@@ -427,6 +441,11 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
send_location(chan);
break;

case MSG_LOCAL_POSITION:
CHECK_PAYLOAD_SIZE(LOCAL_POSITION_NED);
send_local_position(ahrs);
break;

case MSG_NAV_CONTROLLER_OUTPUT:
if (control_mode != MANUAL) {
CHECK_PAYLOAD_SIZE(NAV_CONTROLLER_OUTPUT);
@@ -540,6 +559,13 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
#endif
break;

case MSG_EKF_STATUS_REPORT:
#if AP_AHRS_NAVEKF_AVAILABLE
CHECK_PAYLOAD_SIZE(EKF_STATUS_REPORT);
ahrs.get_NavEKF().send_status_report(chan);
#endif
break;

case MSG_RETRY_DEFERRED:
case MSG_TERRAIN:
case MSG_OPTICAL_FLOW:
@@ -730,6 +756,7 @@ GCS_MAVLINK::data_stream_send(void)
if (stream_trigger(STREAM_POSITION)) {
// sent with GPS read
send_message(MSG_LOCATION);
send_message(MSG_LOCAL_POSITION);
}

if (gcs_out_of_time) return;
@@ -767,6 +794,7 @@ GCS_MAVLINK::data_stream_send(void)
send_message(MSG_SYSTEM_TIME);
send_message(MSG_BATTERY2);
send_message(MSG_MOUNT_STATUS);
send_message(MSG_EKF_STATUS_REPORT);
}
}

@@ -841,15 +869,37 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;

case MAV_CMD_PREFLIGHT_CALIBRATION:
if ((packet.param1 == 1 ||
packet.param2 == 1) &&
packet.param3 == 0) {
startup_INS_ground(true);
if (packet.param1 == 1) {
ins.init_gyro();
if (ins.gyro_calibrated_ok_all()) {
ahrs.reset_gyro_drift();
result = MAV_RESULT_ACCEPTED;
} else {
result = MAV_RESULT_FAILED;
}
} else if (packet.param3 == 1) {
init_barometer();
result = MAV_RESULT_ACCEPTED;
} else if (packet.param4 == 1) {
trim_radio();
result = MAV_RESULT_ACCEPTED;
} else {
} else if (packet.param5 == 1) {
float trim_roll, trim_pitch;
AP_InertialSensor_UserInteract_MAVLink interact(this);
if (g.skip_gyro_cal) {
// start with gyro calibration, otherwise if the user
// has SKIP_GYRO_CAL=1 they don't get to do it
ins.init_gyro();
}
if(ins.calibrate_accel(&interact, trim_roll, trim_pitch)) {
// reset ahrs's trim to suggested values from calibration routine
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
result = MAV_RESULT_ACCEPTED;
} else {
result = MAV_RESULT_FAILED;
}
}
else {
send_text_P(SEVERITY_LOW, PSTR("Unsupported preflight calibration"));
}
break;
@@ -1105,13 +1155,13 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
#if CAMERA == ENABLED
case MAVLINK_MSG_ID_DIGICAM_CONFIGURE:
{
camera.configure_msg(msg);
break;
}

case MAVLINK_MSG_ID_DIGICAM_CONTROL:
{
camera.control_msg(msg);
log_picture();
break;
}
#endif // CAMERA == ENABLED
@@ -1157,8 +1207,17 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case MAVLINK_MSG_ID_SERIAL_CONTROL:
handle_serial_control(msg, gps);
break;

case MAVLINK_MSG_ID_GPS_INJECT_DATA:
handle_gps_inject(msg, gps);
break;

#endif

case MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS:
rover.DataFlash.remote_log_block_status_msg(chan, msg);
break;

case MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST:
gcs[chan-MAVLINK_COMM_0].send_autopilot_version();
break;
@@ -1232,7 +1291,7 @@ static void gcs_update(void)
for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) {
#if CLI_ENABLED == ENABLED
gcs[i].update(run_cli);
gcs[i].update(g.cli_enabled==1?run_cli:NULL);
#else
gcs[i].update(NULL);
#endif
Loading