diff --git a/ArduBoat/.cproject b/ArduBoat/.cproject
new file mode 100644
index 0000000000..adf5adc365
--- /dev/null
+++ b/ArduBoat/.cproject
@@ -0,0 +1,46 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/ArduBoat/.project b/ArduBoat/.project
new file mode 100644
index 0000000000..969ff0d90c
--- /dev/null
+++ b/ArduBoat/.project
@@ -0,0 +1,79 @@
+
+
+ ArduBoat
+
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.genmakebuilder
+ clean,full,incremental,
+
+
+ ?name?
+
+
+
+ org.eclipse.cdt.make.core.append_environment
+ true
+
+
+ org.eclipse.cdt.make.core.autoBuildTarget
+ all
+
+
+ org.eclipse.cdt.make.core.buildArguments
+
+
+
+ org.eclipse.cdt.make.core.buildCommand
+ make
+
+
+ org.eclipse.cdt.make.core.cleanBuildTarget
+ clean
+
+
+ org.eclipse.cdt.make.core.contents
+ org.eclipse.cdt.make.core.activeConfigSettings
+
+
+ org.eclipse.cdt.make.core.enableAutoBuild
+ false
+
+
+ org.eclipse.cdt.make.core.enableCleanBuild
+ true
+
+
+ org.eclipse.cdt.make.core.enableFullBuild
+ true
+
+
+ org.eclipse.cdt.make.core.fullBuildTarget
+ all
+
+
+ org.eclipse.cdt.make.core.stopOnError
+ true
+
+
+ org.eclipse.cdt.make.core.useDefaultBuildCmd
+ true
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
+ full,incremental,
+
+
+
+
+
+ org.eclipse.cdt.core.cnature
+ org.eclipse.cdt.core.ccnature
+ org.eclipse.cdt.managedbuilder.core.managedBuildNature
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
+
+
diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde
index 04a1774322..1c568b2635 100644
--- a/ArduCopter/ArduCopter.pde
+++ b/ArduCopter/ArduCopter.pde
@@ -65,6 +65,7 @@ And much more so PLEASE PM me on DIYDRONES to add your contribution to the List
#include // Range finder library
#include // Optical Flow library
#include
+#include // APM relay
#include // MAVLink GCS definitions
#include
@@ -502,6 +503,8 @@ static byte counter_one_herz;
static bool GPS_enabled = false;
static bool new_radio_frame;
+AP_Relay relay;
+
////////////////////////////////////////////////////////////////////////////////
// Top-level logic
////////////////////////////////////////////////////////////////////////////////
@@ -1328,8 +1331,8 @@ static void tuning(){
case CH6_RELAY:
g.rc_6.set_range(0,1000);
- if (g.rc_6.control_in > 525) relay_on();
- if (g.rc_6.control_in < 475) relay_off();
+ if (g.rc_6.control_in > 525) relay.on();
+ if (g.rc_6.control_in < 475) relay.off();
break;
case CH6_TRAVERSE_SPEED:
diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde
index e381534a47..17d3ac1b99 100644
--- a/ArduCopter/commands_logic.pde
+++ b/ArduCopter/commands_logic.pde
@@ -693,11 +693,11 @@ static void do_set_servo()
static void do_set_relay()
{
if (next_command.p1 == 1) {
- relay_on();
+ relay.on();
} else if (next_command.p1 == 0) {
- relay_off();
+ relay.off();
}else{
- relay_toggle();
+ relay.toggle();
}
}
diff --git a/ArduCopter/events.pde b/ArduCopter/events.pde
index 08357e60ad..d6ae523c54 100644
--- a/ArduCopter/events.pde
+++ b/ArduCopter/events.pde
@@ -75,26 +75,11 @@ static void update_events() // Used for MAV_CMD_DO_REPEAT_SERVO and MAV_CMD_DO_R
}
if (event_id == RELAY_TOGGLE) {
- relay_toggle();
+ relay.toggle();
}
}
}
-static void relay_on()
-{
- PORTL |= B00000100;
-}
-
-static void relay_off()
-{
- PORTL &= ~B00000100;
-}
-
-static void relay_toggle()
-{
- PORTL ^= B00000100;
-}
-
#if PIEZO == ENABLED
void piezo_on()
{
diff --git a/ArduCopter/test.pde b/ArduCopter/test.pde
index a075f10a29..7b2884a9f7 100644
--- a/ArduCopter/test.pde
+++ b/ArduCopter/test.pde
@@ -712,14 +712,14 @@ test_relay(uint8_t argc, const Menu::arg *argv)
while(1){
Serial.printf_P(PSTR("Relay on\n"));
- relay_on();
+ relay.on();
delay(3000);
if(Serial.available() > 0){
return (0);
}
Serial.printf_P(PSTR("Relay off\n"));
- relay_off();
+ relay.off();
delay(3000);
if(Serial.available() > 0){
return (0);
diff --git a/ArduPlane/test.pde b/ArduPlane/test.pde
index 3b95d9c6c0..9c0adbd26d 100644
--- a/ArduPlane/test.pde
+++ b/ArduPlane/test.pde
@@ -279,14 +279,14 @@ test_relay(uint8_t argc, const Menu::arg *argv)
while(1){
Serial.printf_P(PSTR("Relay on\n"));
- relay_on();
+ relay.on();
delay(3000);
if(Serial.available() > 0){
return (0);
}
Serial.printf_P(PSTR("Relay off\n"));
- relay_off();
+ relay.off();
delay(3000);
if(Serial.available() > 0){
return (0);
diff --git a/ArduRover/.cproject b/ArduRover/.cproject
new file mode 100644
index 0000000000..7a4dd5232b
--- /dev/null
+++ b/ArduRover/.cproject
@@ -0,0 +1,46 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/ArduRover/.project b/ArduRover/.project
new file mode 100644
index 0000000000..4494bc9869
--- /dev/null
+++ b/ArduRover/.project
@@ -0,0 +1,79 @@
+
+
+ ArduRover
+
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.genmakebuilder
+ clean,full,incremental,
+
+
+ ?name?
+
+
+
+ org.eclipse.cdt.make.core.append_environment
+ true
+
+
+ org.eclipse.cdt.make.core.autoBuildTarget
+ all
+
+
+ org.eclipse.cdt.make.core.buildArguments
+
+
+
+ org.eclipse.cdt.make.core.buildCommand
+ make
+
+
+ org.eclipse.cdt.make.core.cleanBuildTarget
+ clean
+
+
+ org.eclipse.cdt.make.core.contents
+ org.eclipse.cdt.make.core.activeConfigSettings
+
+
+ org.eclipse.cdt.make.core.enableAutoBuild
+ false
+
+
+ org.eclipse.cdt.make.core.enableCleanBuild
+ true
+
+
+ org.eclipse.cdt.make.core.enableFullBuild
+ true
+
+
+ org.eclipse.cdt.make.core.fullBuildTarget
+ all
+
+
+ org.eclipse.cdt.make.core.stopOnError
+ true
+
+
+ org.eclipse.cdt.make.core.useDefaultBuildCmd
+ true
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
+ full,incremental,
+
+
+
+
+
+ org.eclipse.cdt.core.cnature
+ org.eclipse.cdt.core.ccnature
+ org.eclipse.cdt.managedbuilder.core.managedBuildNature
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
+
+
diff --git a/apo/.cproject b/apo/.cproject
new file mode 100644
index 0000000000..00f2f875be
--- /dev/null
+++ b/apo/.cproject
@@ -0,0 +1,46 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/apo/.project b/apo/.project
new file mode 100644
index 0000000000..4152e256c1
--- /dev/null
+++ b/apo/.project
@@ -0,0 +1,79 @@
+
+
+ apo
+
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.genmakebuilder
+ clean,full,incremental,
+
+
+ ?name?
+
+
+
+ org.eclipse.cdt.make.core.append_environment
+ true
+
+
+ org.eclipse.cdt.make.core.autoBuildTarget
+ all
+
+
+ org.eclipse.cdt.make.core.buildArguments
+
+
+
+ org.eclipse.cdt.make.core.buildCommand
+ make
+
+
+ org.eclipse.cdt.make.core.cleanBuildTarget
+ clean
+
+
+ org.eclipse.cdt.make.core.contents
+ org.eclipse.cdt.make.core.activeConfigSettings
+
+
+ org.eclipse.cdt.make.core.enableAutoBuild
+ false
+
+
+ org.eclipse.cdt.make.core.enableCleanBuild
+ true
+
+
+ org.eclipse.cdt.make.core.enableFullBuild
+ true
+
+
+ org.eclipse.cdt.make.core.fullBuildTarget
+ all
+
+
+ org.eclipse.cdt.make.core.stopOnError
+ true
+
+
+ org.eclipse.cdt.make.core.useDefaultBuildCmd
+ true
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
+ full,incremental,
+
+
+
+
+
+ org.eclipse.cdt.core.cnature
+ org.eclipse.cdt.core.ccnature
+ org.eclipse.cdt.managedbuilder.core.managedBuildNature
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
+
+
diff --git a/libraries/APM_RC/APM_RC.cpp b/libraries/APM_RC/APM_RC.cpp
index 27de25875d..db81cd1852 100644
--- a/libraries/APM_RC/APM_RC.cpp
+++ b/libraries/APM_RC/APM_RC.cpp
@@ -28,34 +28,42 @@
#else
// Variable definition for Input Capture interrupt
-volatile unsigned int ICR4_old;
-volatile unsigned char PPM_Counter=0;
-volatile uint16_t PWM_RAW[8] = {2400,2400,2400,2400,2400,2400,2400,2400};
-volatile unsigned char radio_status=0;
+//volatile uint16_t ICR4_old;
+//volatile uint8_t PPM_Counter=0;
+volatile uint16_t PWM_RAW[NUM_CHANNELS] = {2400,2400,2400,2400,2400,2400,2400,2400};
+volatile uint8_t radio_status=0;
/****************************************************
Input Capture Interrupt ICP4 => PPM signal read
****************************************************/
ISR(TIMER4_CAPT_vect)
{
- unsigned int Pulse;
- unsigned int Pulse_Width;
+ static uint16_t ICR4_old;
+ static uint8_t PPM_Counter=0;
+ uint16_t Pulse;
+ uint16_t Pulse_Width;
+
Pulse=ICR4;
- if (Pulse8000) // SYNC pulse?
+ if (Pulse8000) { // SYNC pulse?
PPM_Counter=0;
- else
- {
- if (PPM_Counter < (sizeof(PWM_RAW) / sizeof(PWM_RAW[0]))) {
- PWM_RAW[PPM_Counter++]=Pulse_Width; //Saving pulse.
- if (PPM_Counter >= NUM_CHANNELS)
- radio_status = 1;
+ }
+ else {
+ if (PPM_Counter < NUM_CHANNELS) { // Valid pulse channel?
+ PWM_RAW[PPM_Counter++]=Pulse_Width; // Saving pulse.
+
+ if (PPM_Counter >= NUM_CHANNELS) {
+ radio_status = 1;
}
}
+ }
ICR4_old = Pulse;
}
@@ -124,7 +132,7 @@ void APM_RC_Class::Init(void)
TIMSK4 |= (1<>1; // Because timer runs at 0.5us we need to do value/2
- result2 = PWM_RAW[ch]>>1;
- if (result != result2)
- result = PWM_RAW[ch]>>1; // if the results are different we make a third reading (this should be fine)
-
+ result = PWM_RAW[ch];
+ if (result != PWM_RAW[ch]) {
+ result = PWM_RAW[ch]; // if the results are different we make a third reading (this should be fine)
+ }
+ result >>= 1; // Because timer runs at 0.5us we need to do value/2
+
// Limit values to a valid range
result = constrain(result,MIN_PULSEWIDTH,MAX_PULSEWIDTH);
radio_status=0; // Radio channel read
return(result);
}
-unsigned char APM_RC_Class::GetState(void)
+uint8_t APM_RC_Class::GetState(void)
{
return(radio_status);
}
@@ -198,7 +206,7 @@ void APM_RC_Class::Force_Out6_Out7(void)
bool APM_RC_Class::setHIL(int16_t v[NUM_CHANNELS])
{
uint8_t sum = 0;
- for (unsigned char i=0; i