mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
changed SENSOR_SIGN to match Jani's setup, updated limits to arm/disarm motors from transmitter, removed #define for Jani's frame (will just use his setup), updated X mode motor control to match new gyro setup
git-svn-id: https://arducopter.googlecode.com/svn/trunk@289 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
bb2f1dfcc1
commit
26f8fb800f
@ -30,10 +30,6 @@
|
|||||||
/**************************************************************/
|
/**************************************************************/
|
||||||
// Special features that might disapear in future releases
|
// Special features that might disapear in future releases
|
||||||
|
|
||||||
//#define jpframe // This is only Jani's special frame, you should never use unless you know what you are doing
|
|
||||||
// As default this should be always checked off.
|
|
||||||
|
|
||||||
|
|
||||||
/* APM Hardware definitions */
|
/* APM Hardware definitions */
|
||||||
#define LED_Yellow 36
|
#define LED_Yellow 36
|
||||||
#define LED_Red 35
|
#define LED_Red 35
|
||||||
@ -54,17 +50,9 @@
|
|||||||
uint8_t sensors[6] = {1, 2, 0, 4, 5, 6}; // For ArduPilot Mega Sensor Shield Hardware
|
uint8_t sensors[6] = {1, 2, 0, 4, 5, 6}; // For ArduPilot Mega Sensor Shield Hardware
|
||||||
|
|
||||||
// Sensor: GYROX, GYROY, GYROZ, ACCELX, ACCELY, ACCELZ, MAGX, MAGY, MAGZ
|
// Sensor: GYROX, GYROY, GYROZ, ACCELX, ACCELY, ACCELZ, MAGX, MAGY, MAGZ
|
||||||
|
|
||||||
#ifndef jpframe
|
|
||||||
int SENSOR_SIGN[]={
|
|
||||||
1, -1, -1, -1, 1, 1, -1, -1, -1};
|
|
||||||
//{-1,1,-1,1,-1,1,-1,-1,-1};
|
|
||||||
#else
|
|
||||||
int SENSOR_SIGN[]={
|
int SENSOR_SIGN[]={
|
||||||
1, -1, 1, -1, 1, 1, -1, -1, -1};
|
1, -1, 1, -1, 1, 1, -1, -1, -1};
|
||||||
//{-1,1,-1,1,-1,1,-1,-1,-1};
|
//{-1,1,-1,1,-1,1,-1,-1,-1};
|
||||||
#endif
|
|
||||||
|
|
||||||
/* APM Hardware definitions, END */
|
/* APM Hardware definitions, END */
|
||||||
|
|
||||||
/* General definitions */
|
/* General definitions */
|
||||||
|
@ -57,8 +57,6 @@
|
|||||||
|
|
||||||
#define CONFIGURATOR // Do se use Configurator or normal text output over serial link
|
#define CONFIGURATOR // Do se use Configurator or normal text output over serial link
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/**********************************************/
|
/**********************************************/
|
||||||
// Not in use yet, starting to work with battery monitors and pressure sensors.
|
// Not in use yet, starting to work with battery monitors and pressure sensors.
|
||||||
// Added 19-08-2010
|
// Added 19-08-2010
|
||||||
@ -72,8 +70,8 @@
|
|||||||
/* User definable modules - END */
|
/* User definable modules - END */
|
||||||
|
|
||||||
// Frame build condiguration
|
// Frame build condiguration
|
||||||
//#define FLIGHT_MODE_+ // Traditional "one arm as nose" frame configuration
|
#define FLIGHT_MODE_+ // Traditional "one arm as nose" frame configuration
|
||||||
#define FLIGHT_MODE_X // Frame orientation 45 deg to CCW, nose between two arms
|
//#define FLIGHT_MODE_X // Frame orientation 45 deg to CCW, nose between two arms
|
||||||
|
|
||||||
|
|
||||||
/* ****************************************************************************** */
|
/* ****************************************************************************** */
|
||||||
@ -99,7 +97,7 @@
|
|||||||
#include "UserConfig.h"
|
#include "UserConfig.h"
|
||||||
|
|
||||||
/* Software version */
|
/* Software version */
|
||||||
#define VER 1.32 // Current software version (only numeric values)
|
#define VER 1.33 // Current software version (only numeric values)
|
||||||
|
|
||||||
|
|
||||||
/* ***************************************************************************** */
|
/* ***************************************************************************** */
|
||||||
@ -631,7 +629,7 @@ void loop(){
|
|||||||
control_yaw = 0;
|
control_yaw = 0;
|
||||||
command_rx_yaw = ToDeg(yaw);
|
command_rx_yaw = ToDeg(yaw);
|
||||||
command_rx_yaw_diff = 0;
|
command_rx_yaw_diff = 0;
|
||||||
if (ch_yaw > 1800) {
|
if (ch_yaw < 1200) {
|
||||||
if (Arming_counter > ARM_DELAY){
|
if (Arming_counter > ARM_DELAY){
|
||||||
motorArmed = 1;
|
motorArmed = 1;
|
||||||
minThrottle = 1100;
|
minThrottle = 1100;
|
||||||
@ -642,7 +640,7 @@ void loop(){
|
|||||||
else
|
else
|
||||||
Arming_counter=0;
|
Arming_counter=0;
|
||||||
// To Disarm motor output : Throttle down and full yaw left for more than 2 seconds
|
// To Disarm motor output : Throttle down and full yaw left for more than 2 seconds
|
||||||
if (ch_yaw < 1200) {
|
if (ch_yaw > 1800) {
|
||||||
if (Disarming_counter > DISARM_DELAY){
|
if (Disarming_counter > DISARM_DELAY){
|
||||||
motorArmed = 0;
|
motorArmed = 0;
|
||||||
minThrottle = MIN_THROTTLE;
|
minThrottle = MIN_THROTTLE;
|
||||||
@ -659,7 +657,6 @@ void loop(){
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Quadcopter mix
|
// Quadcopter mix
|
||||||
// Ask Jose if we still need this IF statement, and if we want to do an ESC calibration
|
|
||||||
if (motorArmed == 1) {
|
if (motorArmed == 1) {
|
||||||
#ifdef IsAM
|
#ifdef IsAM
|
||||||
digitalWrite(FR_LED, HIGH); // AM-Mode
|
digitalWrite(FR_LED, HIGH); // AM-Mode
|
||||||
@ -671,10 +668,10 @@ void loop(){
|
|||||||
backMotor = constrain(ch_throttle - control_pitch + control_yaw, minThrottle, 2000);
|
backMotor = constrain(ch_throttle - control_pitch + control_yaw, minThrottle, 2000);
|
||||||
#endif
|
#endif
|
||||||
#ifdef FLIGHT_MODE_X
|
#ifdef FLIGHT_MODE_X
|
||||||
frontMotor = constrain(ch_throttle + control_roll + control_pitch - control_yaw, minThrottle, 2000); // front left motor
|
rightMotor = constrain(ch_throttle - control_roll + control_pitch - control_yaw, minThrottle, 2000); // front right motor
|
||||||
rightMotor = constrain(ch_throttle - control_roll + control_pitch + control_yaw, minThrottle, 2000); // front right motor
|
leftMotor = constrain(ch_throttle + control_roll - control_pitch - control_yaw, minThrottle, 2000); // rear left motor
|
||||||
leftMotor = constrain(ch_throttle + control_roll - control_pitch + control_yaw, minThrottle, 2000); // rear left motor
|
frontMotor = constrain(ch_throttle + control_roll + control_pitch + control_yaw, minThrottle, 2000); // front left motor
|
||||||
backMotor = constrain(ch_throttle - control_roll - control_pitch - control_yaw, minThrottle, 2000); // rear right motor
|
backMotor = constrain(ch_throttle - control_roll - control_pitch + control_yaw, minThrottle, 2000); // rear right motor
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
if (motorArmed == 0) {
|
if (motorArmed == 0) {
|
||||||
|
Loading…
Reference in New Issue
Block a user