mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Merge branch 'master' of https://code.google.com/p/ardupilot-mega
This commit is contained in:
commit
e5b66c1c7c
46
ArduBoat/.cproject
Normal file
46
ArduBoat/.cproject
Normal file
@ -0,0 +1,46 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<?fileVersion 4.0.0?>
|
||||||
|
|
||||||
|
<cproject storage_type_id="org.eclipse.cdt.core.XmlProjectDescriptionStorage">
|
||||||
|
<storageModule moduleId="org.eclipse.cdt.core.settings">
|
||||||
|
<cconfiguration id="de.innot.avreclipse.toolchain.winavr.base.1533666305">
|
||||||
|
<storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="de.innot.avreclipse.toolchain.winavr.base.1533666305" moduleId="org.eclipse.cdt.core.settings" name="Default">
|
||||||
|
<externalSettings/>
|
||||||
|
<extensions>
|
||||||
|
<extension id="org.eclipse.cdt.core.ELF" point="org.eclipse.cdt.core.BinaryParser"/>
|
||||||
|
<extension id="org.eclipse.cdt.core.MakeErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||||
|
<extension id="org.eclipse.cdt.core.GCCErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||||
|
<extension id="org.eclipse.cdt.core.GASErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||||
|
</extensions>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
|
||||||
|
<configuration buildProperties="" id="de.innot.avreclipse.toolchain.winavr.base.1533666305" name="Default" parent="org.eclipse.cdt.build.core.emptycfg">
|
||||||
|
<folderInfo id="de.innot.avreclipse.toolchain.winavr.base.1533666305.1285523098" name="/" resourcePath="">
|
||||||
|
<toolChain id="de.innot.avreclipse.toolchain.winavr.base.709070025" name="de.innot.avreclipse.toolchain.winavr.base" superClass="de.innot.avreclipse.toolchain.winavr.base">
|
||||||
|
<option id="de.innot.avreclipse.toolchain.options.toolchain.objcopy.flash.719217910" name="Generate HEX file for Flash memory" superClass="de.innot.avreclipse.toolchain.options.toolchain.objcopy.flash"/>
|
||||||
|
<option id="de.innot.avreclipse.toolchain.options.toolchain.objcopy.eeprom.1341673369" name="Generate HEX file for EEPROM" superClass="de.innot.avreclipse.toolchain.options.toolchain.objcopy.eeprom"/>
|
||||||
|
<option id="de.innot.avreclipse.toolchain.options.toolchain.objdump.2067341223" name="Generate Extended Listing (Source + generated Assembler)" superClass="de.innot.avreclipse.toolchain.options.toolchain.objdump"/>
|
||||||
|
<option id="de.innot.avreclipse.toolchain.options.toolchain.size.633135206" name="Print Size" superClass="de.innot.avreclipse.toolchain.options.toolchain.size"/>
|
||||||
|
<option id="de.innot.avreclipse.toolchain.options.toolchain.avrdude.1739936429" name="AVRDude" superClass="de.innot.avreclipse.toolchain.options.toolchain.avrdude"/>
|
||||||
|
<targetPlatform archList="all" binaryParser="org.eclipse.cdt.core.ELF" id="de.innot.avreclipse.targetplatform.avr.901466393" name="AVR Cross-Target" osList="all" superClass="de.innot.avreclipse.targetplatform.avr"/>
|
||||||
|
<builder id="de.innot.avreclipse.target.builder.winavr.base.223268681" managedBuildOn="false" name="AVR GNU Make Builder.Default" superClass="de.innot.avreclipse.target.builder.winavr.base"/>
|
||||||
|
<tool id="de.innot.avreclipse.tool.assembler.winavr.base.314488324" name="AVR Assembler" superClass="de.innot.avreclipse.tool.assembler.winavr.base"/>
|
||||||
|
<tool id="de.innot.avreclipse.tool.compiler.winavr.base.1115835243" name="AVR Compiler" superClass="de.innot.avreclipse.tool.compiler.winavr.base"/>
|
||||||
|
<tool id="de.innot.avreclipse.tool.cppcompiler.base.32469750" name="AVR C++ Compiler" superClass="de.innot.avreclipse.tool.cppcompiler.base"/>
|
||||||
|
<tool id="de.innot.avreclipse.tool.linker.winavr.base.433788290" name="AVR C Linker" superClass="de.innot.avreclipse.tool.linker.winavr.base"/>
|
||||||
|
<tool id="de.innot.avreclipse.tool.cpplinker.base.1828818850" name="AVR C++ Linker" superClass="de.innot.avreclipse.tool.cpplinker.base"/>
|
||||||
|
<tool id="de.innot.avreclipse.tool.archiver.winavr.base.1244907926" name="AVR Archiver" superClass="de.innot.avreclipse.tool.archiver.winavr.base"/>
|
||||||
|
</toolChain>
|
||||||
|
</folderInfo>
|
||||||
|
</configuration>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="org.eclipse.cdt.core.externalSettings"/>
|
||||||
|
</cconfiguration>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
|
||||||
|
<project id="ArduBoat.null.1472107738" name="ArduBoat"/>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="scannerConfiguration">
|
||||||
|
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
|
||||||
|
</storageModule>
|
||||||
|
</cproject>
|
79
ArduBoat/.project
Normal file
79
ArduBoat/.project
Normal file
@ -0,0 +1,79 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<projectDescription>
|
||||||
|
<name>ArduBoat</name>
|
||||||
|
<comment></comment>
|
||||||
|
<projects>
|
||||||
|
</projects>
|
||||||
|
<buildSpec>
|
||||||
|
<buildCommand>
|
||||||
|
<name>org.eclipse.cdt.managedbuilder.core.genmakebuilder</name>
|
||||||
|
<triggers>clean,full,incremental,</triggers>
|
||||||
|
<arguments>
|
||||||
|
<dictionary>
|
||||||
|
<key>?name?</key>
|
||||||
|
<value></value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.append_environment</key>
|
||||||
|
<value>true</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.autoBuildTarget</key>
|
||||||
|
<value>all</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.buildArguments</key>
|
||||||
|
<value></value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.buildCommand</key>
|
||||||
|
<value>make</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.cleanBuildTarget</key>
|
||||||
|
<value>clean</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.contents</key>
|
||||||
|
<value>org.eclipse.cdt.make.core.activeConfigSettings</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.enableAutoBuild</key>
|
||||||
|
<value>false</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.enableCleanBuild</key>
|
||||||
|
<value>true</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.enableFullBuild</key>
|
||||||
|
<value>true</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.fullBuildTarget</key>
|
||||||
|
<value>all</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.stopOnError</key>
|
||||||
|
<value>true</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.useDefaultBuildCmd</key>
|
||||||
|
<value>true</value>
|
||||||
|
</dictionary>
|
||||||
|
</arguments>
|
||||||
|
</buildCommand>
|
||||||
|
<buildCommand>
|
||||||
|
<name>org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder</name>
|
||||||
|
<triggers>full,incremental,</triggers>
|
||||||
|
<arguments>
|
||||||
|
</arguments>
|
||||||
|
</buildCommand>
|
||||||
|
</buildSpec>
|
||||||
|
<natures>
|
||||||
|
<nature>org.eclipse.cdt.core.cnature</nature>
|
||||||
|
<nature>org.eclipse.cdt.core.ccnature</nature>
|
||||||
|
<nature>org.eclipse.cdt.managedbuilder.core.managedBuildNature</nature>
|
||||||
|
<nature>org.eclipse.cdt.managedbuilder.core.ScannerConfigNature</nature>
|
||||||
|
</natures>
|
||||||
|
</projectDescription>
|
@ -65,6 +65,7 @@ And much more so PLEASE PM me on DIYDRONES to add your contribution to the List
|
|||||||
#include <AP_RangeFinder.h> // Range finder library
|
#include <AP_RangeFinder.h> // Range finder library
|
||||||
#include <AP_OpticalFlow.h> // Optical Flow library
|
#include <AP_OpticalFlow.h> // Optical Flow library
|
||||||
#include <ModeFilter.h>
|
#include <ModeFilter.h>
|
||||||
|
#include <AP_Relay.h> // APM relay
|
||||||
#include <GCS_MAVLink.h> // MAVLink GCS definitions
|
#include <GCS_MAVLink.h> // MAVLink GCS definitions
|
||||||
#include <memcheck.h>
|
#include <memcheck.h>
|
||||||
|
|
||||||
@ -502,6 +503,8 @@ static byte counter_one_herz;
|
|||||||
static bool GPS_enabled = false;
|
static bool GPS_enabled = false;
|
||||||
static bool new_radio_frame;
|
static bool new_radio_frame;
|
||||||
|
|
||||||
|
AP_Relay relay;
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
// Top-level logic
|
// Top-level logic
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
@ -1328,8 +1331,8 @@ static void tuning(){
|
|||||||
|
|
||||||
case CH6_RELAY:
|
case CH6_RELAY:
|
||||||
g.rc_6.set_range(0,1000);
|
g.rc_6.set_range(0,1000);
|
||||||
if (g.rc_6.control_in > 525) relay_on();
|
if (g.rc_6.control_in > 525) relay.on();
|
||||||
if (g.rc_6.control_in < 475) relay_off();
|
if (g.rc_6.control_in < 475) relay.off();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case CH6_TRAVERSE_SPEED:
|
case CH6_TRAVERSE_SPEED:
|
||||||
|
@ -693,11 +693,11 @@ static void do_set_servo()
|
|||||||
static void do_set_relay()
|
static void do_set_relay()
|
||||||
{
|
{
|
||||||
if (next_command.p1 == 1) {
|
if (next_command.p1 == 1) {
|
||||||
relay_on();
|
relay.on();
|
||||||
} else if (next_command.p1 == 0) {
|
} else if (next_command.p1 == 0) {
|
||||||
relay_off();
|
relay.off();
|
||||||
}else{
|
}else{
|
||||||
relay_toggle();
|
relay.toggle();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -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) {
|
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
|
#if PIEZO == ENABLED
|
||||||
void piezo_on()
|
void piezo_on()
|
||||||
{
|
{
|
||||||
|
@ -712,14 +712,14 @@ test_relay(uint8_t argc, const Menu::arg *argv)
|
|||||||
|
|
||||||
while(1){
|
while(1){
|
||||||
Serial.printf_P(PSTR("Relay on\n"));
|
Serial.printf_P(PSTR("Relay on\n"));
|
||||||
relay_on();
|
relay.on();
|
||||||
delay(3000);
|
delay(3000);
|
||||||
if(Serial.available() > 0){
|
if(Serial.available() > 0){
|
||||||
return (0);
|
return (0);
|
||||||
}
|
}
|
||||||
|
|
||||||
Serial.printf_P(PSTR("Relay off\n"));
|
Serial.printf_P(PSTR("Relay off\n"));
|
||||||
relay_off();
|
relay.off();
|
||||||
delay(3000);
|
delay(3000);
|
||||||
if(Serial.available() > 0){
|
if(Serial.available() > 0){
|
||||||
return (0);
|
return (0);
|
||||||
|
@ -279,14 +279,14 @@ test_relay(uint8_t argc, const Menu::arg *argv)
|
|||||||
|
|
||||||
while(1){
|
while(1){
|
||||||
Serial.printf_P(PSTR("Relay on\n"));
|
Serial.printf_P(PSTR("Relay on\n"));
|
||||||
relay_on();
|
relay.on();
|
||||||
delay(3000);
|
delay(3000);
|
||||||
if(Serial.available() > 0){
|
if(Serial.available() > 0){
|
||||||
return (0);
|
return (0);
|
||||||
}
|
}
|
||||||
|
|
||||||
Serial.printf_P(PSTR("Relay off\n"));
|
Serial.printf_P(PSTR("Relay off\n"));
|
||||||
relay_off();
|
relay.off();
|
||||||
delay(3000);
|
delay(3000);
|
||||||
if(Serial.available() > 0){
|
if(Serial.available() > 0){
|
||||||
return (0);
|
return (0);
|
||||||
|
46
ArduRover/.cproject
Normal file
46
ArduRover/.cproject
Normal file
@ -0,0 +1,46 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<?fileVersion 4.0.0?>
|
||||||
|
|
||||||
|
<cproject storage_type_id="org.eclipse.cdt.core.XmlProjectDescriptionStorage">
|
||||||
|
<storageModule moduleId="org.eclipse.cdt.core.settings">
|
||||||
|
<cconfiguration id="de.innot.avreclipse.toolchain.winavr.base.594686435">
|
||||||
|
<storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="de.innot.avreclipse.toolchain.winavr.base.594686435" moduleId="org.eclipse.cdt.core.settings" name="Default">
|
||||||
|
<externalSettings/>
|
||||||
|
<extensions>
|
||||||
|
<extension id="org.eclipse.cdt.core.ELF" point="org.eclipse.cdt.core.BinaryParser"/>
|
||||||
|
<extension id="org.eclipse.cdt.core.MakeErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||||
|
<extension id="org.eclipse.cdt.core.GCCErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||||
|
<extension id="org.eclipse.cdt.core.GASErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||||
|
</extensions>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
|
||||||
|
<configuration buildProperties="" id="de.innot.avreclipse.toolchain.winavr.base.594686435" name="Default" parent="org.eclipse.cdt.build.core.emptycfg">
|
||||||
|
<folderInfo id="de.innot.avreclipse.toolchain.winavr.base.594686435.1498078133" name="/" resourcePath="">
|
||||||
|
<toolChain id="de.innot.avreclipse.toolchain.winavr.base.689630969" name="de.innot.avreclipse.toolchain.winavr.base" superClass="de.innot.avreclipse.toolchain.winavr.base">
|
||||||
|
<option id="de.innot.avreclipse.toolchain.options.toolchain.objcopy.flash.1566359540" name="Generate HEX file for Flash memory" superClass="de.innot.avreclipse.toolchain.options.toolchain.objcopy.flash"/>
|
||||||
|
<option id="de.innot.avreclipse.toolchain.options.toolchain.objcopy.eeprom.765758890" name="Generate HEX file for EEPROM" superClass="de.innot.avreclipse.toolchain.options.toolchain.objcopy.eeprom"/>
|
||||||
|
<option id="de.innot.avreclipse.toolchain.options.toolchain.objdump.840297081" name="Generate Extended Listing (Source + generated Assembler)" superClass="de.innot.avreclipse.toolchain.options.toolchain.objdump"/>
|
||||||
|
<option id="de.innot.avreclipse.toolchain.options.toolchain.size.379504817" name="Print Size" superClass="de.innot.avreclipse.toolchain.options.toolchain.size"/>
|
||||||
|
<option id="de.innot.avreclipse.toolchain.options.toolchain.avrdude.1978944089" name="AVRDude" superClass="de.innot.avreclipse.toolchain.options.toolchain.avrdude"/>
|
||||||
|
<targetPlatform archList="all" binaryParser="org.eclipse.cdt.core.ELF" id="de.innot.avreclipse.targetplatform.avr.1167300306" name="AVR Cross-Target" osList="all" superClass="de.innot.avreclipse.targetplatform.avr"/>
|
||||||
|
<builder id="de.innot.avreclipse.target.builder.winavr.base.1810593476" managedBuildOn="false" name="AVR GNU Make Builder.Default" superClass="de.innot.avreclipse.target.builder.winavr.base"/>
|
||||||
|
<tool id="de.innot.avreclipse.tool.assembler.winavr.base.583552593" name="AVR Assembler" superClass="de.innot.avreclipse.tool.assembler.winavr.base"/>
|
||||||
|
<tool id="de.innot.avreclipse.tool.compiler.winavr.base.745023243" name="AVR Compiler" superClass="de.innot.avreclipse.tool.compiler.winavr.base"/>
|
||||||
|
<tool id="de.innot.avreclipse.tool.cppcompiler.base.789662243" name="AVR C++ Compiler" superClass="de.innot.avreclipse.tool.cppcompiler.base"/>
|
||||||
|
<tool id="de.innot.avreclipse.tool.linker.winavr.base.2119909020" name="AVR C Linker" superClass="de.innot.avreclipse.tool.linker.winavr.base"/>
|
||||||
|
<tool id="de.innot.avreclipse.tool.cpplinker.base.1744690341" name="AVR C++ Linker" superClass="de.innot.avreclipse.tool.cpplinker.base"/>
|
||||||
|
<tool id="de.innot.avreclipse.tool.archiver.winavr.base.1982272787" name="AVR Archiver" superClass="de.innot.avreclipse.tool.archiver.winavr.base"/>
|
||||||
|
</toolChain>
|
||||||
|
</folderInfo>
|
||||||
|
</configuration>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="org.eclipse.cdt.core.externalSettings"/>
|
||||||
|
</cconfiguration>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
|
||||||
|
<project id="ArduRover.null.866863111" name="ArduRover"/>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="scannerConfiguration">
|
||||||
|
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
|
||||||
|
</storageModule>
|
||||||
|
</cproject>
|
79
ArduRover/.project
Normal file
79
ArduRover/.project
Normal file
@ -0,0 +1,79 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<projectDescription>
|
||||||
|
<name>ArduRover</name>
|
||||||
|
<comment></comment>
|
||||||
|
<projects>
|
||||||
|
</projects>
|
||||||
|
<buildSpec>
|
||||||
|
<buildCommand>
|
||||||
|
<name>org.eclipse.cdt.managedbuilder.core.genmakebuilder</name>
|
||||||
|
<triggers>clean,full,incremental,</triggers>
|
||||||
|
<arguments>
|
||||||
|
<dictionary>
|
||||||
|
<key>?name?</key>
|
||||||
|
<value></value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.append_environment</key>
|
||||||
|
<value>true</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.autoBuildTarget</key>
|
||||||
|
<value>all</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.buildArguments</key>
|
||||||
|
<value></value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.buildCommand</key>
|
||||||
|
<value>make</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.cleanBuildTarget</key>
|
||||||
|
<value>clean</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.contents</key>
|
||||||
|
<value>org.eclipse.cdt.make.core.activeConfigSettings</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.enableAutoBuild</key>
|
||||||
|
<value>false</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.enableCleanBuild</key>
|
||||||
|
<value>true</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.enableFullBuild</key>
|
||||||
|
<value>true</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.fullBuildTarget</key>
|
||||||
|
<value>all</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.stopOnError</key>
|
||||||
|
<value>true</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.useDefaultBuildCmd</key>
|
||||||
|
<value>true</value>
|
||||||
|
</dictionary>
|
||||||
|
</arguments>
|
||||||
|
</buildCommand>
|
||||||
|
<buildCommand>
|
||||||
|
<name>org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder</name>
|
||||||
|
<triggers>full,incremental,</triggers>
|
||||||
|
<arguments>
|
||||||
|
</arguments>
|
||||||
|
</buildCommand>
|
||||||
|
</buildSpec>
|
||||||
|
<natures>
|
||||||
|
<nature>org.eclipse.cdt.core.cnature</nature>
|
||||||
|
<nature>org.eclipse.cdt.core.ccnature</nature>
|
||||||
|
<nature>org.eclipse.cdt.managedbuilder.core.managedBuildNature</nature>
|
||||||
|
<nature>org.eclipse.cdt.managedbuilder.core.ScannerConfigNature</nature>
|
||||||
|
</natures>
|
||||||
|
</projectDescription>
|
46
apo/.cproject
Normal file
46
apo/.cproject
Normal file
@ -0,0 +1,46 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||||
|
<?fileVersion 4.0.0?>
|
||||||
|
|
||||||
|
<cproject storage_type_id="org.eclipse.cdt.core.XmlProjectDescriptionStorage">
|
||||||
|
<storageModule moduleId="org.eclipse.cdt.core.settings">
|
||||||
|
<cconfiguration id="de.innot.avreclipse.toolchain.winavr.base.394129733">
|
||||||
|
<storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="de.innot.avreclipse.toolchain.winavr.base.394129733" moduleId="org.eclipse.cdt.core.settings" name="Default">
|
||||||
|
<externalSettings/>
|
||||||
|
<extensions>
|
||||||
|
<extension id="org.eclipse.cdt.core.ELF" point="org.eclipse.cdt.core.BinaryParser"/>
|
||||||
|
<extension id="org.eclipse.cdt.core.MakeErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||||
|
<extension id="org.eclipse.cdt.core.GCCErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||||
|
<extension id="org.eclipse.cdt.core.GASErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
|
||||||
|
</extensions>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
|
||||||
|
<configuration buildProperties="" id="de.innot.avreclipse.toolchain.winavr.base.394129733" name="Default" parent="org.eclipse.cdt.build.core.emptycfg">
|
||||||
|
<folderInfo id="de.innot.avreclipse.toolchain.winavr.base.394129733.231173920" name="/" resourcePath="">
|
||||||
|
<toolChain id="de.innot.avreclipse.toolchain.winavr.base.1572708284" name="de.innot.avreclipse.toolchain.winavr.base" superClass="de.innot.avreclipse.toolchain.winavr.base">
|
||||||
|
<option id="de.innot.avreclipse.toolchain.options.toolchain.objcopy.flash.630916939" name="Generate HEX file for Flash memory" superClass="de.innot.avreclipse.toolchain.options.toolchain.objcopy.flash"/>
|
||||||
|
<option id="de.innot.avreclipse.toolchain.options.toolchain.objcopy.eeprom.1019241228" name="Generate HEX file for EEPROM" superClass="de.innot.avreclipse.toolchain.options.toolchain.objcopy.eeprom"/>
|
||||||
|
<option id="de.innot.avreclipse.toolchain.options.toolchain.objdump.1029096770" name="Generate Extended Listing (Source + generated Assembler)" superClass="de.innot.avreclipse.toolchain.options.toolchain.objdump"/>
|
||||||
|
<option id="de.innot.avreclipse.toolchain.options.toolchain.size.1221033519" name="Print Size" superClass="de.innot.avreclipse.toolchain.options.toolchain.size"/>
|
||||||
|
<option id="de.innot.avreclipse.toolchain.options.toolchain.avrdude.1918477271" name="AVRDude" superClass="de.innot.avreclipse.toolchain.options.toolchain.avrdude"/>
|
||||||
|
<targetPlatform archList="all" binaryParser="org.eclipse.cdt.core.ELF" id="de.innot.avreclipse.targetplatform.avr.439246581" name="AVR Cross-Target" osList="all" superClass="de.innot.avreclipse.targetplatform.avr"/>
|
||||||
|
<builder id="de.innot.avreclipse.target.builder.winavr.base.666588525" managedBuildOn="false" name="AVR GNU Make Builder.Default" superClass="de.innot.avreclipse.target.builder.winavr.base"/>
|
||||||
|
<tool id="de.innot.avreclipse.tool.assembler.winavr.base.530847775" name="AVR Assembler" superClass="de.innot.avreclipse.tool.assembler.winavr.base"/>
|
||||||
|
<tool id="de.innot.avreclipse.tool.compiler.winavr.base.752046336" name="AVR Compiler" superClass="de.innot.avreclipse.tool.compiler.winavr.base"/>
|
||||||
|
<tool id="de.innot.avreclipse.tool.cppcompiler.base.920729075" name="AVR C++ Compiler" superClass="de.innot.avreclipse.tool.cppcompiler.base"/>
|
||||||
|
<tool id="de.innot.avreclipse.tool.linker.winavr.base.778684722" name="AVR C Linker" superClass="de.innot.avreclipse.tool.linker.winavr.base"/>
|
||||||
|
<tool id="de.innot.avreclipse.tool.cpplinker.base.1086108831" name="AVR C++ Linker" superClass="de.innot.avreclipse.tool.cpplinker.base"/>
|
||||||
|
<tool id="de.innot.avreclipse.tool.archiver.winavr.base.2066059097" name="AVR Archiver" superClass="de.innot.avreclipse.tool.archiver.winavr.base"/>
|
||||||
|
</toolChain>
|
||||||
|
</folderInfo>
|
||||||
|
</configuration>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="org.eclipse.cdt.core.externalSettings"/>
|
||||||
|
</cconfiguration>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
|
||||||
|
<project id="apo.null.958255624" name="apo"/>
|
||||||
|
</storageModule>
|
||||||
|
<storageModule moduleId="scannerConfiguration">
|
||||||
|
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
|
||||||
|
</storageModule>
|
||||||
|
</cproject>
|
79
apo/.project
Normal file
79
apo/.project
Normal file
@ -0,0 +1,79 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<projectDescription>
|
||||||
|
<name>apo</name>
|
||||||
|
<comment></comment>
|
||||||
|
<projects>
|
||||||
|
</projects>
|
||||||
|
<buildSpec>
|
||||||
|
<buildCommand>
|
||||||
|
<name>org.eclipse.cdt.managedbuilder.core.genmakebuilder</name>
|
||||||
|
<triggers>clean,full,incremental,</triggers>
|
||||||
|
<arguments>
|
||||||
|
<dictionary>
|
||||||
|
<key>?name?</key>
|
||||||
|
<value></value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.append_environment</key>
|
||||||
|
<value>true</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.autoBuildTarget</key>
|
||||||
|
<value>all</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.buildArguments</key>
|
||||||
|
<value></value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.buildCommand</key>
|
||||||
|
<value>make</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.cleanBuildTarget</key>
|
||||||
|
<value>clean</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.contents</key>
|
||||||
|
<value>org.eclipse.cdt.make.core.activeConfigSettings</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.enableAutoBuild</key>
|
||||||
|
<value>false</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.enableCleanBuild</key>
|
||||||
|
<value>true</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.enableFullBuild</key>
|
||||||
|
<value>true</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.fullBuildTarget</key>
|
||||||
|
<value>all</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.stopOnError</key>
|
||||||
|
<value>true</value>
|
||||||
|
</dictionary>
|
||||||
|
<dictionary>
|
||||||
|
<key>org.eclipse.cdt.make.core.useDefaultBuildCmd</key>
|
||||||
|
<value>true</value>
|
||||||
|
</dictionary>
|
||||||
|
</arguments>
|
||||||
|
</buildCommand>
|
||||||
|
<buildCommand>
|
||||||
|
<name>org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder</name>
|
||||||
|
<triggers>full,incremental,</triggers>
|
||||||
|
<arguments>
|
||||||
|
</arguments>
|
||||||
|
</buildCommand>
|
||||||
|
</buildSpec>
|
||||||
|
<natures>
|
||||||
|
<nature>org.eclipse.cdt.core.cnature</nature>
|
||||||
|
<nature>org.eclipse.cdt.core.ccnature</nature>
|
||||||
|
<nature>org.eclipse.cdt.managedbuilder.core.managedBuildNature</nature>
|
||||||
|
<nature>org.eclipse.cdt.managedbuilder.core.ScannerConfigNature</nature>
|
||||||
|
</natures>
|
||||||
|
</projectDescription>
|
@ -28,34 +28,42 @@
|
|||||||
#else
|
#else
|
||||||
|
|
||||||
// Variable definition for Input Capture interrupt
|
// Variable definition for Input Capture interrupt
|
||||||
volatile unsigned int ICR4_old;
|
//volatile uint16_t ICR4_old;
|
||||||
volatile unsigned char PPM_Counter=0;
|
//volatile uint8_t PPM_Counter=0;
|
||||||
volatile uint16_t PWM_RAW[8] = {2400,2400,2400,2400,2400,2400,2400,2400};
|
volatile uint16_t PWM_RAW[NUM_CHANNELS] = {2400,2400,2400,2400,2400,2400,2400,2400};
|
||||||
volatile unsigned char radio_status=0;
|
volatile uint8_t radio_status=0;
|
||||||
|
|
||||||
/****************************************************
|
/****************************************************
|
||||||
Input Capture Interrupt ICP4 => PPM signal read
|
Input Capture Interrupt ICP4 => PPM signal read
|
||||||
****************************************************/
|
****************************************************/
|
||||||
ISR(TIMER4_CAPT_vect)
|
ISR(TIMER4_CAPT_vect)
|
||||||
{
|
{
|
||||||
unsigned int Pulse;
|
static uint16_t ICR4_old;
|
||||||
unsigned int Pulse_Width;
|
static uint8_t PPM_Counter=0;
|
||||||
|
|
||||||
|
uint16_t Pulse;
|
||||||
|
uint16_t Pulse_Width;
|
||||||
|
|
||||||
Pulse=ICR4;
|
Pulse=ICR4;
|
||||||
if (Pulse<ICR4_old) // Take care of the overflow of Timer4 (TOP=40000)
|
if (Pulse<ICR4_old) { // Take care of the overflow of Timer4 (TOP=40000)
|
||||||
Pulse_Width=(Pulse + 40000)-ICR4_old; //Calculating pulse
|
Pulse_Width=(Pulse + 40000)-ICR4_old; // Calculating pulse
|
||||||
else
|
}
|
||||||
Pulse_Width=Pulse-ICR4_old; //Calculating pulse
|
else {
|
||||||
if (Pulse_Width>8000) // SYNC pulse?
|
Pulse_Width=Pulse-ICR4_old; // Calculating pulse
|
||||||
|
}
|
||||||
|
|
||||||
|
if (Pulse_Width>8000) { // SYNC pulse?
|
||||||
PPM_Counter=0;
|
PPM_Counter=0;
|
||||||
else
|
}
|
||||||
{
|
else {
|
||||||
if (PPM_Counter < (sizeof(PWM_RAW) / sizeof(PWM_RAW[0]))) {
|
if (PPM_Counter < NUM_CHANNELS) { // Valid pulse channel?
|
||||||
PWM_RAW[PPM_Counter++]=Pulse_Width; //Saving pulse.
|
PWM_RAW[PPM_Counter++]=Pulse_Width; // Saving pulse.
|
||||||
if (PPM_Counter >= NUM_CHANNELS)
|
|
||||||
radio_status = 1;
|
if (PPM_Counter >= NUM_CHANNELS) {
|
||||||
|
radio_status = 1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
ICR4_old = Pulse;
|
ICR4_old = Pulse;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -124,7 +132,7 @@ void APM_RC_Class::Init(void)
|
|||||||
TIMSK4 |= (1<<ICIE4); // Enable Input Capture interrupt. Timer interrupt mask
|
TIMSK4 |= (1<<ICIE4); // Enable Input Capture interrupt. Timer interrupt mask
|
||||||
}
|
}
|
||||||
|
|
||||||
void APM_RC_Class::OutputCh(unsigned char ch, uint16_t pwm)
|
void APM_RC_Class::OutputCh(uint8_t ch, uint16_t pwm)
|
||||||
{
|
{
|
||||||
pwm=constrain(pwm,MIN_PULSEWIDTH,MAX_PULSEWIDTH);
|
pwm=constrain(pwm,MIN_PULSEWIDTH,MAX_PULSEWIDTH);
|
||||||
pwm<<=1; // pwm*2;
|
pwm<<=1; // pwm*2;
|
||||||
@ -145,29 +153,29 @@ void APM_RC_Class::OutputCh(unsigned char ch, uint16_t pwm)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t APM_RC_Class::InputCh(unsigned char ch)
|
uint16_t APM_RC_Class::InputCh(uint8_t ch)
|
||||||
{
|
{
|
||||||
uint16_t result;
|
uint16_t result;
|
||||||
uint16_t result2;
|
|
||||||
|
|
||||||
if (_HIL_override[ch] != 0) {
|
if (_HIL_override[ch] != 0) {
|
||||||
return _HIL_override[ch];
|
return _HIL_override[ch];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Because servo pulse variables are 16 bits and the interrupts are running values could be corrupted.
|
// Because servo pulse variables are 16 bits and the interrupts are running values could be corrupted.
|
||||||
// We dont want to stop interrupts to read radio channels so we have to do two readings to be sure that the value is correct...
|
// We dont want to stop interrupts to read radio channels so we have to do two readings to be sure that the value is correct...
|
||||||
result = PWM_RAW[ch]>>1; // Because timer runs at 0.5us we need to do value/2
|
result = PWM_RAW[ch];
|
||||||
result2 = PWM_RAW[ch]>>1;
|
if (result != PWM_RAW[ch]) {
|
||||||
if (result != result2)
|
result = PWM_RAW[ch]; // if the results are different we make a third reading (this should be fine)
|
||||||
result = PWM_RAW[ch]>>1; // 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
|
// Limit values to a valid range
|
||||||
result = constrain(result,MIN_PULSEWIDTH,MAX_PULSEWIDTH);
|
result = constrain(result,MIN_PULSEWIDTH,MAX_PULSEWIDTH);
|
||||||
radio_status=0; // Radio channel read
|
radio_status=0; // Radio channel read
|
||||||
return(result);
|
return(result);
|
||||||
}
|
}
|
||||||
|
|
||||||
unsigned char APM_RC_Class::GetState(void)
|
uint8_t APM_RC_Class::GetState(void)
|
||||||
{
|
{
|
||||||
return(radio_status);
|
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])
|
bool APM_RC_Class::setHIL(int16_t v[NUM_CHANNELS])
|
||||||
{
|
{
|
||||||
uint8_t sum = 0;
|
uint8_t sum = 0;
|
||||||
for (unsigned char i=0; i<NUM_CHANNELS; i++) {
|
for (uint8_t i=0; i<NUM_CHANNELS; i++) {
|
||||||
if (v[i] != -1) {
|
if (v[i] != -1) {
|
||||||
_HIL_override[i] = v[i];
|
_HIL_override[i] = v[i];
|
||||||
}
|
}
|
||||||
@ -216,7 +224,7 @@ bool APM_RC_Class::setHIL(int16_t v[NUM_CHANNELS])
|
|||||||
|
|
||||||
void APM_RC_Class::clearOverride(void)
|
void APM_RC_Class::clearOverride(void)
|
||||||
{
|
{
|
||||||
for (unsigned char i=0; i<NUM_CHANNELS; i++) {
|
for (uint8_t i=0; i<NUM_CHANNELS; i++) {
|
||||||
_HIL_override[i] = 0;
|
_HIL_override[i] = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -26,9 +26,9 @@ class APM_RC_Class
|
|||||||
public:
|
public:
|
||||||
APM_RC_Class();
|
APM_RC_Class();
|
||||||
void Init();
|
void Init();
|
||||||
void OutputCh(unsigned char ch, uint16_t pwm);
|
void OutputCh(uint8_t ch, uint16_t pwm);
|
||||||
uint16_t InputCh(unsigned char ch);
|
uint16_t InputCh(uint8_t ch);
|
||||||
unsigned char GetState();
|
uint8_t GetState();
|
||||||
void Force_Out0_Out1(void);
|
void Force_Out0_Out1(void);
|
||||||
void Force_Out2_Out3(void);
|
void Force_Out2_Out3(void);
|
||||||
void Force_Out6_Out7(void);
|
void Force_Out6_Out7(void);
|
||||||
|
Loading…
Reference in New Issue
Block a user