mirror of https://github.com/ArduPilot/ardupilot
Merge some small misc improvements from APM_Camera branch
This commit is contained in:
parent
0f7b317a8d
commit
227ce0a92d
|
@ -1,3 +1,4 @@
|
|||
.metadata/
|
||||
Tools/ArdupilotMegaPlanner/bin/Release/logs/
|
||||
config.mk
|
||||
ArduCopter/Debug/
|
||||
|
|
|
@ -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
|
||||
|
||||
|
|
|
@ -1,5 +1,6 @@
|
|||
/// -*- 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
|
||||
Authors: Jason Short
|
||||
|
|
|
@ -53,7 +53,6 @@ set(${FIRMWARE_NAME}_SKETCHES
|
|||
commands_process.pde
|
||||
control_modes.pde
|
||||
events.pde
|
||||
flight_control.pde
|
||||
flip.pde
|
||||
GCS.pde
|
||||
GCS_Ardupilot.pde
|
||||
|
|
|
@ -83,13 +83,6 @@
|
|||
#define MAX_SONAR_UNKNOWN 0
|
||||
#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_PITCH CH_2
|
||||
#define CH_THROTTLE CH_3
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#define ARM_DELAY 10 // one secon
|
||||
#define DISARM_DELAY 10 // one secon
|
||||
#define ARM_DELAY 10 // one second
|
||||
#define DISARM_DELAY 10 // one second
|
||||
#define LEVEL_DELAY 120 // twelve seconds
|
||||
#define AUTO_LEVEL_DELAY 150 // twentyfive seconds
|
||||
|
||||
|
|
|
@ -41,7 +41,7 @@ const struct Menu::command main_menu_commands[] PROGMEM = {
|
|||
};
|
||||
|
||||
// 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
|
||||
|
||||
|
@ -73,8 +73,8 @@ static void init_ardupilot()
|
|||
Serial1.begin(38400, 128, 16);
|
||||
#endif
|
||||
|
||||
Serial.printf_P(PSTR("\n\nInit ACM"
|
||||
"\n\nRAM: %lu\n"),
|
||||
Serial.printf_P(PSTR("\n\nInit " THISFIRMWARE
|
||||
"\n\nFree RAM: %lu\n"),
|
||||
freeRAM());
|
||||
|
||||
|
||||
|
@ -305,7 +305,9 @@ static void startup_ground(void)
|
|||
// Warm up and read Gyro offsets
|
||||
// -----------------------------
|
||||
imu.init_gyro(mavlink_delay);
|
||||
report_imu();
|
||||
#if CLI_ENABLED == ENABLED
|
||||
report_imu();
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// reset the leds
|
||||
|
|
|
@ -11,6 +11,9 @@ set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Arduino.cmake) # A
|
|||
|
||||
set (CMAKE_CXX_SOURCE_FILE_EXTENSIONS pde)
|
||||
|
||||
|
||||
message(STATUS "DIR: ${CMAKE_SOURCE_DIR}")
|
||||
|
||||
cmake_minimum_required(VERSION 2.8)
|
||||
#====================================================================#
|
||||
# Setup Project #
|
||||
|
@ -50,7 +53,6 @@ set(${FIRMWARE_NAME}_SKETCHES
|
|||
commands_process.pde
|
||||
control_modes.pde
|
||||
events.pde
|
||||
#flight_control.pde
|
||||
#flip.pde
|
||||
#GCS.pde
|
||||
#GCS_Ardupilot.pde
|
||||
|
@ -103,26 +105,26 @@ set(${FIRMWARE_NAME}_LIBS
|
|||
DataFlash
|
||||
AP_Math
|
||||
PID
|
||||
RC_Channel
|
||||
RC_Channel
|
||||
AP_OpticalFlow
|
||||
ModeFilter
|
||||
memcheck
|
||||
memcheck
|
||||
#AP_PID
|
||||
APM_PI
|
||||
#APO
|
||||
FastSerial
|
||||
AP_Common
|
||||
GCS_MAVLink
|
||||
AP_GPS
|
||||
APM_RC
|
||||
AP_DCM
|
||||
AP_ADC
|
||||
AP_Compass
|
||||
AP_IMU
|
||||
AP_RangeFinder
|
||||
APM_BMP085
|
||||
c
|
||||
m
|
||||
FastSerial
|
||||
AP_Common
|
||||
GCS_MAVLink
|
||||
AP_GPS
|
||||
APM_RC
|
||||
AP_DCM
|
||||
AP_ADC
|
||||
AP_Compass
|
||||
AP_IMU
|
||||
AP_RangeFinder
|
||||
APM_BMP085
|
||||
c
|
||||
m
|
||||
)
|
||||
SET_TARGET_PROPERTIES(AP_Math PROPERTIES LINKER_LANGUAGE CXX)
|
||||
|
||||
|
|
|
@ -41,7 +41,7 @@ static const struct Menu::command main_menu_commands[] PROGMEM = {
|
|||
};
|
||||
|
||||
// Create the top-level menu object.
|
||||
MENU(main_menu, "APM trunk", main_menu_commands);
|
||||
MENU(main_menu, THISFIRMWARE, main_menu_commands);
|
||||
|
||||
#endif // CLI_ENABLED
|
||||
|
||||
|
|
|
@ -15,6 +15,8 @@
|
|||
#define CH_6 5
|
||||
#define CH_7 6
|
||||
#define CH_8 7
|
||||
#define CH_10 9 //PB5
|
||||
#define CH_11 10 //PE3
|
||||
|
||||
#include <inttypes.h>
|
||||
|
||||
|
|
|
@ -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_8]] = rc_8;
|
||||
|
||||
//set auxiliary ranges
|
||||
G_RC_AUX(k_flap)->set_range(0,100);
|
||||
G_RC_AUX(k_flap_auto)->set_range(0,100);
|
||||
G_RC_AUX(k_aileron)->set_angle(4500);
|
||||
|
|
Loading…
Reference in New Issue