Skip to content

Commit

Permalink
Initial commit, 3.0.1 R2
Browse files Browse the repository at this point in the history
  • Loading branch information
[email protected] authored and SirAlex committed Sep 25, 2013
1 parent 5d11e05 commit cc8d812
Show file tree
Hide file tree
Showing 114 changed files with 7,775 additions and 70 deletions.
5 changes: 5 additions & 0 deletions APMrover2/APMrover2.pde
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,7 @@ version 2.1 of the License, or (at your option) any later version.
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
#include <AP_HAL_PX4.h>
#include <AP_HAL_MPNG.h>
#include <AP_HAL_Empty.h>
#include "compat.h"

Expand Down Expand Up @@ -129,6 +130,8 @@ static void print_mode(AP_HAL::BetterStream *port, uint8_t mode);
static DataFlash_APM1 DataFlash;
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
static DataFlash_APM2 DataFlash;
#elif CONFIG_HAL_BOARD == HAL_BOARD_MPNG
static DataFlash_MPNG DataFlash;
#elif CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
//static DataFlash_File DataFlash("/tmp/APMlogs");
static DataFlash_SITL DataFlash;
Expand Down Expand Up @@ -203,6 +206,8 @@ AP_GPS_HIL g_gps_driver;

#if CONFIG_INS_TYPE == CONFIG_INS_MPU6000
AP_InertialSensor_MPU6000 ins;
#elif CONFIG_INS_TYPE == CONFIG_INS_MPU6000_I2C
AP_InertialSensor_MPU6000_I2C ins;
#elif CONFIG_INS_TYPE == CONFIG_INS_PX4
AP_InertialSensor_PX4 ins;
#elif CONFIG_INS_TYPE == CONFIG_INS_STUB
Expand Down
15 changes: 15 additions & 0 deletions APMrover2/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,21 @@
# define USB_MUX_PIN 23
# define BATTERY_PIN_1 1
# define CURRENT_PIN_1 2
#elif CONFIG_HAL_BOARD == HAL_BOARD_MPNG
# define A_LED_PIN 13
# define B_LED_PIN 31
# define C_LED_PIN 30
# define LED_ON HIGH
# define LED_OFF LOW
# define USB_MUX_PIN -1
# define BATTERY_VOLT_PIN 0 // Battery voltage on A0
# define BATTERY_CURR_PIN 1 // Battery current on A1
# define CONFIG_INS_TYPE CONFIG_INS_MPU6000_I2C
# define CONFIG_BARO AP_BARO_MS5611
# define CONFIG_MS5611_SERIAL AP_BARO_MS5611_I2C
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define MAGNETOMETER ENABLED
# define CONFIG_COMPASS AP_COMPASS_HMC5843
#elif CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
# define CONFIG_INS_TYPE CONFIG_INS_STUB
# define CONFIG_COMPASS AP_COMPASS_HIL
Expand Down
1 change: 1 addition & 0 deletions APMrover2/defines.h
Original file line number Diff line number Diff line change
Expand Up @@ -204,6 +204,7 @@ enum ap_message {
#define CONFIG_INS_MPU6000 2
#define CONFIG_INS_STUB 3
#define CONFIG_INS_PX4 4
#define CONFIG_INS_MPU6000_I2C 5

// compass driver types
#define AP_COMPASS_HMC5843 1
Expand Down
20 changes: 14 additions & 6 deletions ArduCopter/APM_Config.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,12 +5,20 @@
// If you used to define your CONFIG_APM_HARDWARE setting here, it is no longer
// valid! You should switch to using a HAL_BOARD flag in your local config.mk.

// If you have CRIUS V1 - Uncomment next line to disable logging
#define LOGGING_ENABLED DISABLED // disable logging for boards without dataflash chip

// If Arduino IDE hang while uploading firmware to your board, try to change string below, just enter some random characters
#define BOOTLOADER_BUGFIX "234fs34567hf"

// Currently not supported
#define CONFIG_SONAR DISABLED

//#define HIL_MODE HIL_MODE_SENSORS // build for hardware-in-the-loop simulation
//#define LOGGING_ENABLED DISABLED // disable logging to save code space
//#define DMP_ENABLED ENABLED // use MPU6000's DMP instead of DCM for attitude estimation
//#define SECONDARY_DMP_ENABLED ENABLED // allows running DMP in parallel with DCM for testing purposes
//#define HIL_MODE HIL_MODE_ATTITUDE // build for hardware-in-the-loop simulation

//#define FRAME_CONFIG QUAD_FRAME
// QuadCopter selected by default
//#define FRAME_CONFIG HEXA_FRAME
/*
* options:
* QUAD_FRAME
Expand All @@ -26,9 +34,9 @@
// Put your variable definitions into the UserVariables.h file (or another file name and then change the #define below).
//#define USERHOOK_VARIABLES "UserVariables.h"
// Put your custom code into the UserCode.pde with function names matching those listed below and ensure the appropriate #define below is uncommented below
//#define USERHOOK_INIT userhook_init(); // for code to be run once at startup
//#define USERHOOK_INIT userhook_init(); // for code to be run once at startup
//#define USERHOOK_FASTLOOP userhook_FastLoop(); // for code to be run at 100hz
//#define USERHOOK_50HZLOOP userhook_50Hz(); // for code to be run at 50hz
//#define USERHOOK_50HZLOOP userhook_50Hz(); // for code to be run at 50hz
//#define USERHOOK_MEDIUMLOOP userhook_MediumLoop(); // for code to be run at 10hz
//#define USERHOOK_SLOWLOOP userhook_SlowLoop(); // for code to be run at 3.3hz
//#define USERHOOK_SUPERSLOWLOOP userhook_SuperSlowLoop(); // for code to be run at 1hz
11 changes: 8 additions & 3 deletions ArduCopter/ArduCopter.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 "ArduCopter V3.0.1-rc2"
#define THISFIRMWARE "ArduCopter-MPNG V3.0.1 R2"
/*
* ArduCopter Version 3.0
* Creator: Jason Short
Expand Down Expand Up @@ -67,6 +67,7 @@
// AP_HAL
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_MPNG.h>
#include <AP_HAL_AVR_SITL.h>
#include <AP_HAL_SMACCM.h>
#include <AP_HAL_PX4.h>
Expand Down Expand Up @@ -156,6 +157,8 @@ static void print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode);
static DataFlash_APM2 DataFlash;
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
static DataFlash_APM1 DataFlash;
#elif CONFIG_HAL_BOARD == HAL_BOARD_MPNG
static DataFlash_MPNG DataFlash;
#elif CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
//static DataFlash_File DataFlash("/tmp/APMlogs");
static DataFlash_SITL DataFlash;
Expand Down Expand Up @@ -196,8 +199,10 @@ static AP_Int8 *flight_modes = &g.flight_mode1;
static AP_ADC_ADS7844 adc;
#endif

#if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000
#if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000
static AP_InertialSensor_MPU6000 ins;
#elif CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000_I2C
static AP_InertialSensor_MPU6000_I2C ins;
#elif CONFIG_IMU_TYPE == CONFIG_IMU_OILPAN
static AP_InertialSensor_Oilpan ins(&adc);
#elif CONFIG_IMU_TYPE == CONFIG_IMU_SITL
Expand Down Expand Up @@ -915,7 +920,7 @@ static void barometer_accumulate(void)
}

// enable this to get console logging of scheduler performance
#define SCHEDULER_DEBUG 0
#define SCHEDULER_DEBUG 1

static void perf_update(void)
{
Expand Down
10 changes: 5 additions & 5 deletions ArduCopter/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,16 +1,16 @@
ArduCopter Release Notes:
------------------------------------------------------------------
ArduCopter 3.0.1-rc2 10-Jul-2013
ArduCopter 3.0.1-rc2 / 3.0.1 11-Jul-2013
Improvements over 3.0.1-rc1
1) Rate Roll, Pitch and Yaw I fix when we hit motor limits
2) pre-arm check changes:
a) double flash arming light when pre-arm checks fail
b) relax mag field checks to 35% min, 165% max of expected field
3) loiter and auto changes:
a) reduced Loiter Pos P to 0.8 (was 1.0)
b) reduced Loiter speed to 5 m/s
c) reduced WP_ACCEL to 1 m/s/s (was 250 m/s/s)
d) rounding error fix in loiter controller
a) reduced Loiter speed to 5 m/s
b) reduced WP_ACCEL to 1 m/s/s (was 2.5 m/s/s)
c) rounding error fix in loiter controller
d) bug fix to stopping point calculation for RTL and loiter during missions
4) Stability Patch fix which was freezing Rate Taw I term and allowing uncommanded Yaw
------------------------------------------------------------------
ArduCopter 3.0.1-rc1 26-Jun-2013
Expand Down
48 changes: 24 additions & 24 deletions ArduCopter/commands_logic.pde
Original file line number Diff line number Diff line change
Expand Up @@ -351,6 +351,8 @@ static void do_land(const struct Location *cmd)
// note: caller should set yaw_mode
static void do_loiter_unlimited()
{
Vector3f target_pos;

// set roll-pitch mode (no pilot input)
set_roll_pitch_mode(AUTO_RP);

Expand All @@ -361,26 +363,24 @@ static void do_loiter_unlimited()
set_yaw_mode(YAW_HOLD);

// get current position
// To-Do: change this to projection based on current location and velocity
Vector3f curr = inertial_nav.get_position();
Vector3f curr_pos = inertial_nav.get_position();

// default to use position provided
Vector3f pos = pv_location_to_vector(command_nav_queue);
// use current location if not provided
if(command_nav_queue.lat == 0 && command_nav_queue.lng == 0) {
wp_nav.get_stopping_point(curr_pos,inertial_nav.get_velocity(),target_pos);
}else{
// default to use position provided
target_pos = pv_location_to_vector(command_nav_queue);
}

// use current altitude if not provided
if( command_nav_queue.alt == 0 ) {
pos.z = curr.z;
}

// use current location if not provided
if(command_nav_queue.lat == 0 && command_nav_queue.lng == 0) {
pos.x = curr.x;
pos.y = curr.y;
target_pos.z = curr_pos.z;
}

// start way point navigator and provide it the desired location
set_nav_mode(NAV_WP);
wp_nav.set_destination(pos);
wp_nav.set_destination(target_pos);
}

// do_circle - initiate moving in a circle
Expand Down Expand Up @@ -419,6 +419,8 @@ static void do_circle()
// note: caller should set yaw_mode
static void do_loiter_time()
{
Vector3f target_pos;

// set roll-pitch mode (no pilot input)
set_roll_pitch_mode(AUTO_RP);

Expand All @@ -429,26 +431,24 @@ static void do_loiter_time()
set_yaw_mode(YAW_HOLD);

// get current position
// To-Do: change this to projection based on current location and velocity
Vector3f curr = inertial_nav.get_position();
Vector3f curr_pos = inertial_nav.get_position();

// default to use position provided
Vector3f pos = pv_location_to_vector(command_nav_queue);
// use current location if not provided
if(command_nav_queue.lat == 0 && command_nav_queue.lng == 0) {
wp_nav.get_stopping_point(curr_pos,inertial_nav.get_velocity(),target_pos);
}else{
// default to use position provided
target_pos = pv_location_to_vector(command_nav_queue);
}

// use current altitude if not provided
if( command_nav_queue.alt == 0 ) {
pos.z = curr.z;
}

// use current location if not provided
if(command_nav_queue.lat == 0 && command_nav_queue.lng == 0) {
pos.x = curr.x;
pos.y = curr.y;
target_pos.z = curr_pos.z;
}

// start way point navigator and provide it the desired location
set_nav_mode(NAV_WP);
wp_nav.set_destination(pos);
wp_nav.set_destination(target_pos);

// setup loiter timer
loiter_time = 0;
Expand Down
29 changes: 24 additions & 5 deletions ArduCopter/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,15 @@
# define CONFIG_RELAY DISABLED
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define MAGNETOMETER ENABLED
#elif CONFIG_HAL_BOARD == HAL_BOARD_MPNG
# define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000_I2C
# define CONFIG_BARO AP_BARO_MS5611
# define CONFIG_MS5611_SERIAL AP_BARO_MS5611_I2C
# define CONFIG_ADC DISABLED
# define CONFIG_PUSHBUTTON DISABLED
# define CONFIG_RELAY DISABLED
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define MAGNETOMETER ENABLED
#elif CONFIG_HAL_BOARD == HAL_BOARD_SMACCM
# define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000
# define CONFIG_BARO AP_BARO_MS5611
Expand Down Expand Up @@ -170,6 +179,16 @@
# define USB_MUX_PIN -1
# define BATTERY_VOLT_PIN 0 // Battery voltage on A0
# define BATTERY_CURR_PIN 1 // Battery current on A1
#elif CONFIG_HAL_BOARD == HAL_BOARD_MPNG
# define A_LED_PIN 13
# define B_LED_PIN 31
# define C_LED_PIN 30
# define LED_ON HIGH
# define LED_OFF LOW
# define PUSHBUTTON_PIN (-1)
# define USB_MUX_PIN (-1)
# define BATTERY_VOLT_PIN 0 // Battery voltage on A0
# define BATTERY_CURR_PIN 1 // Battery current on A1
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
# define A_LED_PIN 27
# define B_LED_PIN 26
Expand Down Expand Up @@ -218,7 +237,7 @@
//

#ifndef COPTER_LEDS
#define COPTER_LEDS ENABLED
#define COPTER_LEDS DISABLED
#endif

#define COPTER_LED_ON HIGH
Expand All @@ -233,7 +252,7 @@
#define COPTER_LED_6 AN9 // Motor LED
#define COPTER_LED_7 AN10 // Motor LED
#define COPTER_LED_8 AN11 // Motor LED
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL || CONFIG_HAL_BOARD == HAL_BOARD_PX4 || HAL_BOARD_SMACCM
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_MPNG || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL || CONFIG_HAL_BOARD == HAL_BOARD_PX4 || HAL_BOARD_SMACCM
#define COPTER_LED_1 AN8 // Motor or Aux LED
#define COPTER_LED_2 AN9 // Motor LED
#define COPTER_LED_3 AN10 // Motor or GPS LED
Expand Down Expand Up @@ -435,7 +454,7 @@
//////////////////////////////////////////////////////////////////////////////
// OPTICAL_FLOW
#if defined( __AVR_ATmega2560__ ) // determines if optical flow code is included
#define OPTFLOW ENABLED
#define OPTFLOW DISABLED
#endif
#ifndef OPTFLOW // sets global enabled/disabled flag for optflow (as seen in CLI)
# define OPTFLOW DISABLED
Expand Down Expand Up @@ -831,7 +850,7 @@
# define RATE_YAW_P 0.200f
#endif
#ifndef RATE_YAW_I
# define RATE_YAW_I 0.015f
# define RATE_YAW_I 0.020f
#endif
#ifndef RATE_YAW_D
# define RATE_YAW_D 0.000f
Expand Down Expand Up @@ -873,7 +892,7 @@
// Loiter position control gains
//
#ifndef LOITER_P
# define LOITER_P 0.8f
# define LOITER_P 1.0f
#endif
#ifndef LOITER_I
# define LOITER_I 0.0f
Expand Down
1 change: 1 addition & 0 deletions ArduCopter/defines.h
Original file line number Diff line number Diff line change
Expand Up @@ -403,6 +403,7 @@ enum ap_message {
#define CONFIG_IMU_MPU6000 2
#define CONFIG_IMU_SITL 3
#define CONFIG_IMU_PX4 4
#define CONFIG_IMU_MPU6000_I2C 5

#define AP_BARO_BMP085 1
#define AP_BARO_MS5611 2
Expand Down
2 changes: 2 additions & 0 deletions ArduCopter/perf_info.pde
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,9 @@ void perf_info_check_loop_time(uint32_t time_in_micros)
perf_info_max_time = time_in_micros;
}
if( time_in_micros > PERF_INFO_OVERTIME_THRESHOLD_MICROS ) {
hal.gpio->write(45,1);
perf_info_long_running++;
hal.gpio->write(45,0);
}
}

Expand Down
2 changes: 2 additions & 0 deletions ArduCopter/setup.pde
Original file line number Diff line number Diff line change
Expand Up @@ -189,7 +189,9 @@ setup_compassmot(uint8_t argc, const Menu::arg *argv)
}

// initialise compass
hal.scheduler->suspend_timer_procs();
init_compass();
hal.scheduler->resume_timer_procs();

// disable motor compensation
compass.motor_compensation_type(AP_COMPASS_MOT_COMP_DISABLED);
Expand Down
7 changes: 6 additions & 1 deletion ArduCopter/system.pde
Original file line number Diff line number Diff line change
Expand Up @@ -190,6 +190,7 @@ static void init_ardupilot()
init_rc_in(); // sets up rc channels from radio
init_rc_out(); // sets up motors and output to escs

cliSerial->println_P(PSTR(BOOTLOADER_BUGFIX));
/*
* setup the 'main loop is dead' check. Note that this relies on
* the RC library being initialised.
Expand All @@ -208,8 +209,12 @@ static void init_ardupilot()
// GPS Initialization
g_gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_1G);

if(g.compass_enabled)
if(g.compass_enabled) {
#if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000_I2C && HIL_MODE == HIL_MODE_DISABLED
ins.hardware_init_i2c_bypass();
#endif
init_compass();
}

// init the optical flow sensor
if(g.optflow_enabled) {
Expand Down
Loading

0 comments on commit cc8d812

Please sign in to comment.