Skip to content

Commit 1641688

Browse files
author
Paku-
committed
Initial sources push at MegaPirateNG Add-Ons V2.9.1b R8.158 20130701
1 parent 1c3a3f5 commit 1641688

File tree

476 files changed

+112757
-0
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

476 files changed

+112757
-0
lines changed

.gitignore

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
/.cproject
2+
/.project

ArduCopter/.gitignore

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
arducopter.cpp

ArduCopter/APM_Config.h

Lines changed: 180 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,180 @@
1+
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2+
#ifndef __ARDUCOPTER_APMCONFIG_H__
3+
#define __ARDUCOPTER_APMCONFIG_H__
4+
5+
// Select your sensor board
6+
#define PIRATES_SENSOR_BOARD PIRATES_CRIUS_AIO_PRO_V1
7+
/*
8+
PIRATES_ALLINONE
9+
PIRATES_FFIMU
10+
PIRATES_FREEIMU
11+
PIRATES_BLACKVORTEX
12+
PIRATES_FREEIMU_4 // New FreeIMU 0.4.1 with MPU6050, MS5611 and 5883L
13+
PIRATES_DROTEK_10DOF_MPU // MPU6050, MS5611 and 5883L
14+
PIRATES_CRIUS_AIO_PRO_V1 // Crius AllInOne Pro v1(1.1)
15+
PIRATES_CRIUS_AIO_PRO_V2 // Crius AllInOne Pro v2
16+
*/
17+
18+
// RC configuration
19+
20+
// PPM_SUM(CPPM) Signal processing
21+
22+
#define SERIAL_PPM SERIAL_PPM_ENABLED
23+
/*
24+
SERIAL_PPM_DISABLED // Std.Rx using more then ONE cable to connect
25+
SERIAL_PPM_ENABLED // For all boards, PPM_SUM pin is A8 (no longer the PL1 is no longer supported for AIO v2)
26+
*/
27+
28+
#define TX_CHANNEL_SET TX_JR
29+
/*
30+
TX_set1 //Graupner/Spektrum PITCH,YAW,THROTTLE,ROLL,AUX1,AUX2,CAMPITCH,CAMROLL
31+
TX_standard //standard PPM layout Robbe/Hitec/Sanwa ROLL,PITCH,THROTTLE,YAW,MODE,AUX2,CAMPITCH,CAMROLL
32+
TX_set2 //some Hitec/Sanwa/others PITCH,ROLL,THROTTLE,YAW,AUX1,AUX2,CAMPITCH,CAMROLL
33+
TX_mwi //MultiWii layout ROLL,THROTTLE,PITCH,YAW,AUX1,AUX2,CAMPITCH,CAMROLL
34+
TX_JR //JR layout FLAPS:MODE, GEAR:SAVE TRIMM = apm ch7
35+
*/
36+
37+
// Select your baro sensor
38+
#define CONFIG_BARO AP_BARO_MS5611_I2C
39+
/*
40+
AP_BARO_BMP085_PIRATES
41+
AP_BARO_MS5611_I2C
42+
*/
43+
44+
// Warning: COPTER_LEDS is not compatible with LED_SEQUENCER, so enable only one option
45+
// Connect LEDs to A4 - A7
46+
#define COPTER_LEDS ENABLED // Native ArduCopter LEDs
47+
//#define LED_SEQUENCER ENABLED // Old Syberian's LED Sequencer, see leds.pde for more info
48+
49+
//### PAKU #########################################################################
50+
// Below there are CPU stress optimization defines.
51+
// Leave Sonar and Gimbal DISABLED if you are not going to use it.
52+
//##################################################################################
53+
// WARNING: Sonar is fully disabled by default now.
54+
#define CONFIG_SONAR DISABLED
55+
/*
56+
DISABLED
57+
ENABLED
58+
*/
59+
#define MAX_SONAR_RANGE 400
60+
61+
// WARNING: Gimbal is fully disabled by default now.
62+
#define CONFIG_GIMBAL DISABLED
63+
/*
64+
DISABLED
65+
ENABLED
66+
*/
67+
68+
// WARNING: Limits code is disabled by default now.
69+
#define AP_LIMITS DISABLED
70+
/*
71+
DISABLED
72+
ENABLED
73+
*/
74+
75+
76+
// This OSD works on the Serial1 port
77+
#define OSD_PROTOCOL OSD_PROTOCOL_FRSKY
78+
/*
79+
OSD_PROTOCOL_NONE
80+
OSD_PROTOCOL_SYBERIAN
81+
OSD_PROTOCOL_REMZIBI // Read more at: http://www.rcgroups.com/forums/showthread.php?t=921467
82+
OSD_PROTOCOL_FRSKY // FrSky Telemetry protocol
83+
*/
84+
85+
// For BlackVortex, just set PIRATES_SENSOR_BOARD as PIRATES_BLACKVORTEX, GPS will be selected automatically
86+
#define GPS_PROTOCOL GPS_PROTOCOL_NMEA
87+
/*
88+
GPS_PROTOCOL_NONE without GPS
89+
GPS_PROTOCOL_NMEA
90+
GPS_PROTOCOL_SIRF
91+
GPS_PROTOCOL_UBLOX
92+
GPS_PROTOCOL_MTK19
93+
GPS_PROTOCOL_BLACKVORTEX
94+
GPS_PROTOCOL_AUTO auto select GPS, may not work
95+
*/
96+
97+
#define SERIAL0_BAUD 115200 // Console port
98+
#define SERIAL2_BAUD 115200 // GPS port
99+
#define SERIAL3_BAUD 57600 // Telemetry (MAVLINK) port
100+
101+
102+
///paku - define LEDs on FIRST firmware upload - could be changed later in Mission Planner
103+
// Join options by "+" sign
104+
//if you change LED_MODE in Mission Planer you will not be able to change it back to these values.
105+
//but only by parameters save,text edit and reload in MP.
106+
107+
#define LEDS_STARTUP_MODE LEDS_MOTORS + LEDS_BEEPER + LEDS_GPS
108+
/*
109+
LEDS_MOTORS
110+
LEDS_GPS
111+
LEDS_AUX
112+
LEDS_BEEPER
113+
LEDS_OSCILLATE
114+
LEDS_MOTORS_ON_NAV
115+
LEDS_GPS_ON_NAV
116+
*/
117+
118+
///PAKU
119+
// motors off delay for STAB mode x/50sec ... give max about 100 = 2 sec
120+
#define STAB_THR_OFF_DELAY 25
121+
122+
#define FRAME_CONFIG QUAD_FRAME
123+
/*
124+
* QUAD_FRAME
125+
* TRI_FRAME
126+
* HEXA_FRAME
127+
* Y6_FRAME
128+
* OCTA_FRAME
129+
* OCTA_QUAD_FRAME
130+
* HELI_FRAME
131+
*/
132+
133+
#define FRAME_ORIENTATION X_FRAME
134+
/*
135+
* PLUS_FRAME
136+
* X_FRAME
137+
* V_FRAME
138+
*/
139+
140+
# define CH7_OPTION CH7_SAVE_TRIM
141+
/*
142+
* CH7_DO_NOTHING
143+
* CH7_FLIP
144+
* CH7_SIMPLE_MODE
145+
* CH7_RTL
146+
* CH7_SAVE_TRIM
147+
* CH7_SAVE_WP
148+
* CH7_CAMERA_TRIGGER
149+
*/
150+
151+
// Inertia based contollers
152+
//#define INERTIAL_NAV_XY ENABLED
153+
#define INERTIAL_NAV_Z ENABLED
154+
155+
// agmatthews USERHOOKS
156+
// the choice of function names is up to the user and does not have to match these
157+
// uncomment these hooks and ensure there is a matching function on your "UserCode.pde" file
158+
//#define USERHOOK_FASTLOOP userhook_FastLoop();
159+
#define USERHOOK_50HZLOOP userhook_50Hz();
160+
//#define USERHOOK_MEDIUMLOOP userhook_MediumLoop();
161+
//#define USERHOOK_SLOWLOOP userhook_SlowLoop();
162+
//#define USERHOOK_SUPERSLOWLOOP userhook_SuperSlowLoop();
163+
#define USERHOOK_INIT userhook_init();
164+
165+
// the choice of included variables file (*.h) is up to the user and does not have to match this one
166+
// Ensure the defined file exists and is in the arducopter directory
167+
#define USERHOOK_VARIABLES "UserVariables.h"
168+
169+
#if PIRATES_SENSOR_BOARD == PIRATES_CRIUS_AIO_PRO_V2
170+
#define LOGGING_ENABLED ENABLED
171+
#else
172+
#define LOGGING_ENABLED DISABLED
173+
#endif
174+
175+
// ************** EXPERIMENTAL FEATURES *****************
176+
177+
// #define LOITER_REPOSITIONING ENABLED // Experimental Do Not Use
178+
// #define LOITER_RP ROLL_PITCH_LOITER_PR // Experimental Do Not Use
179+
180+
#endif //__ARDUCOPTER_APMCONFIG_H__

ArduCopter/APM_Config_mavlink_hil.h

Lines changed: 42 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,42 @@
1+
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2+
3+
// HIL_MODE SELECTION
4+
//
5+
// Mavlink supports
6+
// 1. HIL_MODE_ATTITUDE : simulated position, airspeed, and attitude
7+
// 2. HIL_MODE_SENSORS: full sensor simulation
8+
#define HIL_MODE HIL_MODE_ATTITUDE
9+
10+
// HIL_PORT SELCTION
11+
//
12+
// PORT 1
13+
// If you would like to run telemetry communications for a groundstation
14+
// while you are running hardware in the loop it is necessary to set
15+
// HIL_PORT to 1. This uses the port that would have been used for the gps
16+
// as the hardware in the loop port. You will have to solder
17+
// headers onto the gps port connection on the apm
18+
// and connect via an ftdi cable.
19+
//
20+
// The baud rate is set to 115200 in this mode.
21+
//
22+
// PORT 3
23+
// If you don't require telemetry communication with a gcs while running
24+
// hardware in the loop you may use the telemetry port as the hardware in
25+
// the loop port. Alternatively, use a telemetry/HIL shim like FGShim
26+
// https://ardupilot-mega.googlecode.com/svn/Tools/trunk/FlightGear
27+
//
28+
// The buad rate is controlled by SERIAL3_BAUD in this mode.
29+
30+
#define HIL_PORT 3
31+
32+
// You can set your gps protocol here for your actual
33+
// hardware and leave it without affecting the hardware
34+
// in the loop simulation
35+
#define GPS_PROTOCOL GPS_PROTOCOL_MTK
36+
37+
// Sensors
38+
// All sensors are supported in all modes.
39+
// The magnetometer is not used in
40+
// HIL_MODE_ATTITUDE but you may leave it
41+
// enabled if you wish.
42+
#define MAGNETOMETER ENABLED

ArduCopter/AP_State.pde

Lines changed: 140 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,140 @@
1+
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2+
3+
4+
void set_home_is_set(bool b)
5+
{
6+
ap.home_is_set = b;
7+
8+
if(b) Log_Write_Event(DATA_SET_HOME);
9+
}
10+
11+
// ---------------------------------------------
12+
void set_armed(bool b)
13+
{
14+
ap.armed = b;
15+
if(b){
16+
Log_Write_Event(DATA_ARMED);
17+
18+
}else{
19+
Log_Write_Event(DATA_DISARMED);
20+
}
21+
}
22+
23+
// ---------------------------------------------
24+
void set_auto_armed(bool b)
25+
{
26+
ap.auto_armed = b;
27+
if(b){
28+
Log_Write_Event(DATA_AUTO_ARMED);
29+
}
30+
}
31+
32+
// ---------------------------------------------
33+
void set_simple_mode(bool b)
34+
{
35+
if(ap.simple_mode != b){
36+
if(b){
37+
Log_Write_Event(DATA_SET_SIMPLE_ON);
38+
}else{
39+
Log_Write_Event(DATA_SET_SIMPLE_OFF);
40+
}
41+
}
42+
ap.simple_mode = b;
43+
}
44+
45+
// ---------------------------------------------
46+
static void set_failsafe(bool mode)
47+
{
48+
// only act on changes
49+
// -------------------
50+
if(ap.failsafe != mode) {
51+
52+
// store the value so we don't trip the gate twice
53+
// -----------------------------------------------
54+
ap.failsafe = mode;
55+
56+
if (ap.failsafe == false) {
57+
// We've regained radio contact
58+
// ----------------------------
59+
failsafe_off_event();
60+
}else{
61+
// We've lost radio contact
62+
// ------------------------
63+
failsafe_on_event();
64+
}
65+
}
66+
}
67+
68+
69+
// ---------------------------------------------
70+
void set_low_battery(bool b)
71+
{
72+
ap.low_battery = b;
73+
}
74+
75+
// ---------------------------------------------
76+
void set_takeoff_complete(bool b)
77+
{
78+
if(b){
79+
Log_Write_Event(DATA_TAKEOFF);
80+
}
81+
ap.takeoff_complete = b;
82+
}
83+
84+
// ---------------------------------------------
85+
void set_land_complete(bool b)
86+
{
87+
if(b){
88+
Log_Write_Event(DATA_LAND_COMPLETE);
89+
}
90+
ap.land_complete = b;
91+
}
92+
93+
// ---------------------------------------------
94+
95+
void set_alt_change(uint8_t flag){
96+
97+
// if no change, exit immediately
98+
if( alt_change_flag == flag ) {
99+
return;
100+
}
101+
102+
// update flag
103+
alt_change_flag = flag;
104+
105+
if(flag == REACHED_ALT){
106+
Log_Write_Event(DATA_REACHED_ALT);
107+
108+
}else if(flag == ASCENDING){
109+
Log_Write_Event(DATA_ASCENDING);
110+
111+
}else if(flag == DESCENDING){
112+
Log_Write_Event(DATA_DESCENDING);
113+
}
114+
}
115+
116+
void set_compass_healthy(bool b)
117+
{
118+
if(ap.compass_status != b){
119+
if(false == b){
120+
Log_Write_Event(DATA_LOST_COMPASS);
121+
}
122+
}
123+
ap.compass_status = b;
124+
}
125+
126+
void set_gps_healthy(bool b)
127+
{
128+
if(ap.gps_status != b){
129+
if(false == b){
130+
Log_Write_Event(DATA_LOST_GPS);
131+
}
132+
}
133+
ap.gps_status = b;
134+
}
135+
136+
void dump_state()
137+
{
138+
cliSerial->printf("st: %u\n",ap.value);
139+
//cliSerial->printf("%u\n", *(uint16_t*)&ap);
140+
}

0 commit comments

Comments
 (0)