mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
undid accidentical commit of local changes
sorry about that! git-svn-id: https://arducopter.googlecode.com/svn/trunk@1806 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
5820e19696
commit
53549f14a6
@ -1,3 +1,28 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
// Example config file. Use APM_Config.h.reference and the wiki to find additional defines to setup your plane.
|
||||||
|
// Once you upload the code, run the factory "reset" to save all config values to EEPROM.
|
||||||
|
// After reset, use the setup mode to set your radio limits for CH1-4, and to set your flight modes.
|
||||||
|
|
||||||
|
// GPS is auto-selected
|
||||||
|
|
||||||
|
#define GCS_PROTOCOL GCS_PROTOCOL_NONE
|
||||||
|
|
||||||
|
//#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_UP_PINS_BACK
|
||||||
|
|
||||||
|
# define SERIAL0_BAUD 38400
|
||||||
|
|
||||||
|
//# define STABILIZE_ROLL_P 0.4
|
||||||
|
//# define STABILIZE_PITCH_P 0.4
|
||||||
|
//# define STABILIZE_DAMPENER 0.1
|
||||||
|
|
||||||
|
|
||||||
|
//#define ACRO_RATE_TRIGGER 4200
|
||||||
|
// if you want full ACRO mode, set value to 0
|
||||||
|
// if you want safe ACRO mode, set value to 100
|
||||||
|
// if you want mostly stabilize with flips, set value to 4200
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
// Logging
|
||||||
|
//#define LOG_CURRENT ENABLED
|
||||||
|
|
||||||
|
|
||||||
#include "configs/tridge.h"
|
|
||||||
|
@ -558,16 +558,3 @@
|
|||||||
#ifndef ALLOW_RC_OVERRIDE
|
#ifndef ALLOW_RC_OVERRIDE
|
||||||
# define ALLOW_RC_OVERRIDE DISABLED
|
# define ALLOW_RC_OVERRIDE DISABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
|
||||||
// Motor arming
|
|
||||||
//
|
|
||||||
// The default is for MODE2 setups. We wait for throttle to reach
|
|
||||||
// zero, and rudder to be at maximum extent.
|
|
||||||
#ifndef MOTOR_ARM_CONDITION
|
|
||||||
# define MOTOR_ARM_CONDITION (g.rc_3.control_in == 0 && g.rc_4.control_in > 2700)
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef MOTOR_DISARM_CONDITION
|
|
||||||
# define MOTOR_DISARM_CONDITION (g.rc_3.control_in == 0 && g.rc_4.control_in < -2700)
|
|
||||||
#endif
|
|
||||||
|
@ -1,49 +0,0 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
|
||||||
|
|
||||||
// Example config file. Use APM_Config.h.reference and the wiki to find additional defines to setup your plane.
|
|
||||||
// Once you upload the code, run the factory "reset" to save all config values to EEPROM.
|
|
||||||
// After reset, use the setup mode to set your radio limits for CH1-4, and to set your flight modes.
|
|
||||||
|
|
||||||
// GPS is auto-selected
|
|
||||||
|
|
||||||
#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
|
|
||||||
|
|
||||||
#define SERIAL0_BAUD 115200
|
|
||||||
#define SERIAL3_BAUD 115200
|
|
||||||
|
|
||||||
// Hardware in the loop protocol
|
|
||||||
#if 0
|
|
||||||
# define HIL_MODE HIL_MODE_NONE
|
|
||||||
#else
|
|
||||||
# define HIL_MODE HIL_MODE_ATTITUDE
|
|
||||||
# define HIL_PROTOCOL HIL_PROTOCOL_MAVLINK
|
|
||||||
# define HIL_PORT 0
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// You can set your gps protocol here for your actual
|
|
||||||
// hardware and leave it without affecting the hardware
|
|
||||||
// in the loop simulation
|
|
||||||
|
|
||||||
// Ground control station comms
|
|
||||||
#define GCS_PROTOCOL GCS_PROTOCOL_MAVLINK
|
|
||||||
#define GCS_PORT 0
|
|
||||||
|
|
||||||
//#define RADIO_OVERRIDE_DEFAULTS { 1500, 1500, 1000, 1500, 1000, 1000, 1000, 1815 }
|
|
||||||
|
|
||||||
#define FLIGHT_MODE_CHANNEL CH_8
|
|
||||||
|
|
||||||
#define FLIGHT_MODE_1 STABILIZE
|
|
||||||
#define FLIGHT_MODE_2 ALT_HOLD
|
|
||||||
#define FLIGHT_MODE_3 ACRO
|
|
||||||
#define FLIGHT_MODE_4 STABILIZE
|
|
||||||
#define FLIGHT_MODE_5 STABILIZE
|
|
||||||
#define FLIGHT_MODE_6 STABILIZE
|
|
||||||
|
|
||||||
//#define ALWAYS_RESET_RADIO_RANGE 1
|
|
||||||
//#define ALWAYS_RESET_MODES 1
|
|
||||||
|
|
||||||
#define GPS_PROTOCOL GPS_PROTOCOL_UBLOX
|
|
||||||
|
|
||||||
// Use MODE1 arming
|
|
||||||
#define MOTOR_ARM_CONDITION (g.rc_3.control_in == 0 && g.rc_1.control_in > 2700)
|
|
||||||
#define MOTOR_DISARM_CONDITION (g.rc_3.control_in == 0 && g.rc_1.control_in < -2700)
|
|
@ -6,14 +6,12 @@ void read_control_switch()
|
|||||||
//motor_armed = (switchPosition < 5);
|
//motor_armed = (switchPosition < 5);
|
||||||
|
|
||||||
if (oldSwitchPosition != switchPosition){
|
if (oldSwitchPosition != switchPosition){
|
||||||
|
|
||||||
set_mode(g.flight_modes[switchPosition]);
|
set_mode(g.flight_modes[switchPosition]);
|
||||||
|
|
||||||
oldSwitchPosition = switchPosition;
|
oldSwitchPosition = switchPosition;
|
||||||
prev_WP = current_loc;
|
prev_WP = current_loc;
|
||||||
|
|
||||||
Serial.print("Changed to flight mode: ");
|
|
||||||
Serial.println(flight_mode_strings[g.flight_modes[switchPosition]]);
|
|
||||||
|
|
||||||
// reset navigation integrators
|
// reset navigation integrators
|
||||||
// -------------------------
|
// -------------------------
|
||||||
reset_I();
|
reset_I();
|
||||||
|
@ -6,29 +6,25 @@
|
|||||||
void arm_motors()
|
void arm_motors()
|
||||||
{
|
{
|
||||||
static byte arming_counter;
|
static byte arming_counter;
|
||||||
// Serial.printf("rc3: %u rc4: %u\n", g.rc_3.control_in, g.rc_4.control_in);
|
|
||||||
// Arm motor output : Throttle down and full yaw right for more than 2 seconds
|
// Arm motor output : Throttle down and full yaw right for more than 2 seconds
|
||||||
if (MOTOR_ARM_CONDITION) {
|
if (g.rc_3.control_in == 0){
|
||||||
|
if (g.rc_4.control_in > 2700) {
|
||||||
if (arming_counter > ARM_DELAY) {
|
if (arming_counter > ARM_DELAY) {
|
||||||
if (!motor_armed) {
|
|
||||||
gcs.send_text(SEVERITY_MEDIUM, "Arming motors");
|
|
||||||
}
|
|
||||||
motor_armed = true;
|
motor_armed = true;
|
||||||
} else{
|
} else{
|
||||||
arming_counter++;
|
arming_counter++;
|
||||||
}
|
}
|
||||||
} else if (MOTOR_DISARM_CONDITION) {
|
}else if (g.rc_4.control_in < -2700) {
|
||||||
if (arming_counter > DISARM_DELAY){
|
if (arming_counter > DISARM_DELAY){
|
||||||
if (motor_armed) {
|
|
||||||
gcs.send_text(SEVERITY_MEDIUM, "Dis-arming motors");
|
|
||||||
}
|
|
||||||
motor_armed = false;
|
motor_armed = false;
|
||||||
} else {
|
}else{
|
||||||
arming_counter++;
|
arming_counter++;
|
||||||
}
|
}
|
||||||
} else {
|
}else{
|
||||||
arming_counter = 0;
|
arming_counter = 0;
|
||||||
}
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -123,22 +123,6 @@ void init_ardupilot()
|
|||||||
|
|
||||||
init_rc_in(); // sets up rc channels from radio
|
init_rc_in(); // sets up rc channels from radio
|
||||||
init_rc_out(); // sets up the timer libs
|
init_rc_out(); // sets up the timer libs
|
||||||
|
|
||||||
#ifdef ALWAYS_RESET_RADIO_RANGE
|
|
||||||
{
|
|
||||||
RC_Channel *rcp = &g.rc_1;
|
|
||||||
for (unsigned char i=0; i<8; i++) {
|
|
||||||
rcp[i].radio_min = 1000;
|
|
||||||
rcp[i].radio_max = 2000;
|
|
||||||
rcp[i].save_eeprom();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef ALWAYS_RESET_MODES
|
|
||||||
default_flight_modes();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
init_camera();
|
init_camera();
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
adc.Init(); // APM ADC library initialization
|
adc.Init(); // APM ADC library initialization
|
||||||
|
Loading…
Reference in New Issue
Block a user