This commit is contained in:
Jason Short 2011-09-17 12:23:22 -07:00
commit da65096ee2
11 changed files with 35 additions and 32 deletions

1
.gitignore vendored
View File

@ -1,3 +1,4 @@
.metadata/ .metadata/
Tools/ArdupilotMegaPlanner/bin/Release/logs/ Tools/ArdupilotMegaPlanner/bin/Release/logs/
config.mk config.mk
ArduCopter/Debug/

View File

@ -1,4 +1,6 @@
// Example config file. Take a look at confi.h. Any term define there can be overridden by defining it here. // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// Example config file. Take a look at config.h. Any term define there can be overridden by defining it here.
// GPS is auto-selected // GPS is auto-selected

View File

@ -1,5 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define THISFIRMWARE "ArduCopter V2.0.43 Beta"
/* /*
ArduCopter Version 2.0 Beta ArduCopter Version 2.0 Beta
Authors: Jason Short Authors: Jason Short

View File

@ -53,7 +53,6 @@ set(${FIRMWARE_NAME}_SKETCHES
commands_process.pde commands_process.pde
control_modes.pde control_modes.pde
events.pde events.pde
flight_control.pde
flip.pde flip.pde
GCS.pde GCS.pde
GCS_Ardupilot.pde GCS_Ardupilot.pde

View File

@ -83,13 +83,6 @@
#define MAX_SONAR_UNKNOWN 0 #define MAX_SONAR_UNKNOWN 0
#define MAX_SONAR_XL 1 #define MAX_SONAR_XL 1
// Radio channels
// Note channels are from 0!
//
// XXX these should be CH_n defines from RC.h at some point.
#define CH_10 9 //PB5
#define CH_11 10 //PE3
#define CH_ROLL CH_1 #define CH_ROLL CH_1
#define CH_PITCH CH_2 #define CH_PITCH CH_2
#define CH_THROTTLE CH_3 #define CH_THROTTLE CH_3

View File

@ -1,7 +1,7 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define ARM_DELAY 10 // one secon #define ARM_DELAY 10 // one second
#define DISARM_DELAY 10 // one secon #define DISARM_DELAY 10 // one second
#define LEVEL_DELAY 120 // twelve seconds #define LEVEL_DELAY 120 // twelve seconds
#define AUTO_LEVEL_DELAY 150 // twentyfive seconds #define AUTO_LEVEL_DELAY 150 // twentyfive seconds

View File

@ -41,7 +41,7 @@ const struct Menu::command main_menu_commands[] PROGMEM = {
}; };
// Create the top-level menu object. // Create the top-level menu object.
MENU(main_menu, "ArduCopter 2.0.43 Beta", main_menu_commands); MENU(main_menu, THISFIRMWARE, main_menu_commands);
#endif // CLI_ENABLED #endif // CLI_ENABLED
@ -73,8 +73,8 @@ static void init_ardupilot()
Serial1.begin(38400, 128, 16); Serial1.begin(38400, 128, 16);
#endif #endif
Serial.printf_P(PSTR("\n\nInit ACM" Serial.printf_P(PSTR("\n\nInit " THISFIRMWARE
"\n\nRAM: %lu\n"), "\n\nFree RAM: %lu\n"),
freeRAM()); freeRAM());
@ -305,7 +305,9 @@ static void startup_ground(void)
// Warm up and read Gyro offsets // Warm up and read Gyro offsets
// ----------------------------- // -----------------------------
imu.init_gyro(mavlink_delay); imu.init_gyro(mavlink_delay);
report_imu(); #if CLI_ENABLED == ENABLED
report_imu();
#endif
#endif #endif
// reset the leds // reset the leds

View File

@ -11,6 +11,9 @@ set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Arduino.cmake) # A
set (CMAKE_CXX_SOURCE_FILE_EXTENSIONS pde) set (CMAKE_CXX_SOURCE_FILE_EXTENSIONS pde)
message(STATUS "DIR: ${CMAKE_SOURCE_DIR}")
cmake_minimum_required(VERSION 2.8) cmake_minimum_required(VERSION 2.8)
#====================================================================# #====================================================================#
# Setup Project # # Setup Project #
@ -50,7 +53,6 @@ set(${FIRMWARE_NAME}_SKETCHES
commands_process.pde commands_process.pde
control_modes.pde control_modes.pde
events.pde events.pde
#flight_control.pde
#flip.pde #flip.pde
#GCS.pde #GCS.pde
#GCS_Ardupilot.pde #GCS_Ardupilot.pde
@ -103,26 +105,26 @@ set(${FIRMWARE_NAME}_LIBS
DataFlash DataFlash
AP_Math AP_Math
PID PID
RC_Channel RC_Channel
AP_OpticalFlow AP_OpticalFlow
ModeFilter ModeFilter
memcheck memcheck
#AP_PID #AP_PID
APM_PI APM_PI
#APO #APO
FastSerial FastSerial
AP_Common AP_Common
GCS_MAVLink GCS_MAVLink
AP_GPS AP_GPS
APM_RC APM_RC
AP_DCM AP_DCM
AP_ADC AP_ADC
AP_Compass AP_Compass
AP_IMU AP_IMU
AP_RangeFinder AP_RangeFinder
APM_BMP085 APM_BMP085
c c
m m
) )
SET_TARGET_PROPERTIES(AP_Math PROPERTIES LINKER_LANGUAGE CXX) SET_TARGET_PROPERTIES(AP_Math PROPERTIES LINKER_LANGUAGE CXX)

View File

@ -41,7 +41,7 @@ static const struct Menu::command main_menu_commands[] PROGMEM = {
}; };
// Create the top-level menu object. // Create the top-level menu object.
MENU(main_menu, "APM trunk", main_menu_commands); MENU(main_menu, THISFIRMWARE, main_menu_commands);
#endif // CLI_ENABLED #endif // CLI_ENABLED

View File

@ -15,6 +15,8 @@
#define CH_6 5 #define CH_6 5
#define CH_7 6 #define CH_7 6
#define CH_8 7 #define CH_8 7
#define CH_10 9 //PB5
#define CH_11 10 //PE3
#include <inttypes.h> #include <inttypes.h>

View File

@ -48,6 +48,7 @@ void update_aux_servo_function(RC_Channel_aux* rc_5, RC_Channel_aux* rc_6, RC_Ch
g_rc_function[aux_servo_function[CH_7]] = rc_7; g_rc_function[aux_servo_function[CH_7]] = rc_7;
g_rc_function[aux_servo_function[CH_8]] = rc_8; g_rc_function[aux_servo_function[CH_8]] = rc_8;
//set auxiliary ranges
G_RC_AUX(k_flap)->set_range(0,100); G_RC_AUX(k_flap)->set_range(0,100);
G_RC_AUX(k_flap_auto)->set_range(0,100); G_RC_AUX(k_flap_auto)->set_range(0,100);
G_RC_AUX(k_aileron)->set_angle(4500); G_RC_AUX(k_aileron)->set_angle(4500);