started adding ledring stuff (yawn). found out i2c was broken, stopped.
default rc input is now pwm (non-nerds won) added deadband to config git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@110 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
fa29022f21
commit
6e88b8ae30
|
@ -504,8 +504,8 @@
|
|||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>0</TopLine>
|
||||
<CurrentLine>0</CurrentLine>
|
||||
<TopLine>1</TopLine>
|
||||
<CurrentLine>1</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\config.c</PathWithFileName>
|
||||
<FilenameWithoutPath>config.c</FilenameWithoutPath>
|
||||
|
@ -558,10 +558,10 @@
|
|||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>45</ColumnNumber>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>55</TopLine>
|
||||
<CurrentLine>55</CurrentLine>
|
||||
<TopLine>124</TopLine>
|
||||
<CurrentLine>129</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\mw.c</PathWithFileName>
|
||||
<FilenameWithoutPath>mw.c</FilenameWithoutPath>
|
||||
|
@ -614,10 +614,10 @@
|
|||
<FileType>5</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<ColumnNumber>20</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>0</TopLine>
|
||||
<CurrentLine>0</CurrentLine>
|
||||
<TopLine>151</TopLine>
|
||||
<CurrentLine>167</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\mw.h</PathWithFileName>
|
||||
<FilenameWithoutPath>mw.h</FilenameWithoutPath>
|
||||
|
@ -649,10 +649,10 @@
|
|||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>16</ColumnNumber>
|
||||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>44</TopLine>
|
||||
<CurrentLine>67</CurrentLine>
|
||||
<CurrentLine>72</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\drv_adxl345.c</PathWithFileName>
|
||||
<FilenameWithoutPath>drv_adxl345.c</FilenameWithoutPath>
|
||||
|
@ -691,10 +691,10 @@
|
|||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>43</ColumnNumber>
|
||||
<ColumnNumber>11</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>122</TopLine>
|
||||
<CurrentLine>149</CurrentLine>
|
||||
<TopLine>121</TopLine>
|
||||
<CurrentLine>121</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\drv_i2c.c</PathWithFileName>
|
||||
<FilenameWithoutPath>drv_i2c.c</FilenameWithoutPath>
|
||||
|
@ -755,6 +755,20 @@
|
|||
<PathWithFileName>.\src\drv_uart.c</PathWithFileName>
|
||||
<FilenameWithoutPath>drv_uart.c</FilenameWithoutPath>
|
||||
</File>
|
||||
<File>
|
||||
<GroupNumber>2</GroupNumber>
|
||||
<FileNumber>0</FileNumber>
|
||||
<FileType>1</FileType>
|
||||
<tvExp>0</tvExp>
|
||||
<Focus>0</Focus>
|
||||
<ColumnNumber>7</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>17</TopLine>
|
||||
<CurrentLine>52</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\drv_ledring.c</PathWithFileName>
|
||||
<FilenameWithoutPath>drv_ledring.c</FilenameWithoutPath>
|
||||
</File>
|
||||
</Group>
|
||||
|
||||
<Group>
|
||||
|
@ -939,7 +953,7 @@
|
|||
<ColumnNumber>0</ColumnNumber>
|
||||
<tvExpOptDlg>0</tvExpOptDlg>
|
||||
<TopLine>133</TopLine>
|
||||
<CurrentLine>133</CurrentLine>
|
||||
<CurrentLine>136</CurrentLine>
|
||||
<bDave2>0</bDave2>
|
||||
<PathWithFileName>.\src\baseflight_startups\startup_stm32f10x_md.s</PathWithFileName>
|
||||
<FilenameWithoutPath>startup_stm32f10x_md.s</FilenameWithoutPath>
|
||||
|
|
|
@ -486,6 +486,11 @@
|
|||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_uart.c</FilePath>
|
||||
</File>
|
||||
<File>
|
||||
<FileName>drv_ledring.c</FileName>
|
||||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_ledring.c</FilePath>
|
||||
</File>
|
||||
</Files>
|
||||
</Group>
|
||||
<Group>
|
||||
|
@ -1040,6 +1045,11 @@
|
|||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_uart.c</FilePath>
|
||||
</File>
|
||||
<File>
|
||||
<FileName>drv_ledring.c</FileName>
|
||||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_ledring.c</FilePath>
|
||||
</File>
|
||||
</Files>
|
||||
</Group>
|
||||
<Group>
|
||||
|
|
|
@ -15,6 +15,7 @@
|
|||
#include "drv_bmp085.h"
|
||||
#include "drv_hmc5883l.h"
|
||||
#include "drv_i2c.h"
|
||||
#include "drv_ledring.h"
|
||||
#include "drv_mpu3050.h"
|
||||
#include "drv_pwm.h"
|
||||
#include "drv_uart.h"
|
||||
|
@ -36,6 +37,7 @@ typedef enum {
|
|||
FEATURE_SERVO_TILT = 1 << 5,
|
||||
FEATURE_CAMTRIG = 1 << 6,
|
||||
FEATURE_GYRO_SMOOTHING = 1 << 7,
|
||||
FEATURE_LED_RING = 1 << 8,
|
||||
} AvailableFeatures;
|
||||
|
||||
#define digitalHi(p, i) { p->BSRR = i; }
|
||||
|
|
|
@ -8,7 +8,7 @@
|
|||
config_t cfg;
|
||||
|
||||
static uint32_t enabledSensors = 0;
|
||||
static uint8_t checkNewConf = 2;
|
||||
static uint8_t checkNewConf = 3;
|
||||
|
||||
void readEEPROM(void)
|
||||
{
|
||||
|
@ -65,7 +65,7 @@ void checkFirstTime(void)
|
|||
cfg.version = checkNewConf;
|
||||
cfg.mixerConfiguration = MULTITYPE_QUADX;
|
||||
featureClearAll();
|
||||
featureSet(FEATURE_VBAT | FEATURE_PPM);
|
||||
featureSet(FEATURE_VBAT); // | FEATURE_PPM); // sadly, this is for hackers only
|
||||
|
||||
cfg.P8[ROLL] = 40;
|
||||
cfg.I8[ROLL] = 30;
|
||||
|
@ -102,8 +102,9 @@ void checkFirstTime(void)
|
|||
cfg.accTrim[1] = 0;
|
||||
cfg.gyro_smoothing_factor = 0x00141403; // default factors of 20, 20, 3 for R/P/Y
|
||||
cfg.powerTrigger1 = 0;
|
||||
|
||||
|
||||
// Radio/ESC
|
||||
cfg.deadband = 0;
|
||||
cfg.midrc = 1500;
|
||||
cfg.minthrottle = 1150;
|
||||
cfg.maxthrottle = 1850;
|
||||
|
|
|
@ -0,0 +1,53 @@
|
|||
#include "board.h"
|
||||
#include "mw.h"
|
||||
|
||||
// Driver for DFRobot I2C Led Ring
|
||||
#define LED_RING_ADDRESS 0x6D
|
||||
|
||||
bool ledringDetect(void)
|
||||
{
|
||||
bool ack = false;
|
||||
uint8_t sig = 'e';
|
||||
|
||||
ack = 0; // i2cWrite(LED_RING_ADDRESS, 0xFF, 1, &sig);
|
||||
if (!ack)
|
||||
return false;
|
||||
return true;
|
||||
}
|
||||
|
||||
void ledringState(void)
|
||||
{
|
||||
uint8_t b[10];
|
||||
static uint8_t state;
|
||||
|
||||
if (state == 0) {
|
||||
b[0] = 'z';
|
||||
b[1] = (180 - heading) / 2; // 1 unit = 2 degrees;
|
||||
// i2cWrite(LED_RING_ADDRESS, 0xFF, 2, b);
|
||||
state = 1;
|
||||
} else if (state == 1) {
|
||||
b[0] = 'y';
|
||||
b[1] = constrain(angle[ROLL] / 10 + 90, 0, 180);
|
||||
b[2] = constrain(angle[PITCH] / 10 + 90, 0, 180);
|
||||
// i2cWrite(LED_RING_ADDRESS, 0xFF, 3, b);
|
||||
state = 2;
|
||||
} else if (state == 2) {
|
||||
b[0] = 'd'; // all unicolor GREEN
|
||||
b[1] = 1;
|
||||
if (armed)
|
||||
b[2] = 1;
|
||||
else
|
||||
b[2] = 0;
|
||||
// i2cWrite(LED_RING_ADDRESS, 0xFF, 3, b);
|
||||
state = 0;
|
||||
}
|
||||
}
|
||||
|
||||
void ledringBlink(void)
|
||||
{
|
||||
uint8_t b[3];
|
||||
b[0] = 'k';
|
||||
b[1] = 10;
|
||||
b[2] = 10;
|
||||
// i2cWrite(LED_RING_ADDRESS, 0xFF, 3, b);
|
||||
}
|
|
@ -0,0 +1,5 @@
|
|||
#pragma once
|
||||
|
||||
bool ledringDetect(void);
|
||||
void ledringState(void);
|
||||
void ledringBlink(void);
|
12
src/mw.c
12
src/mw.c
|
@ -126,13 +126,13 @@ void annexCode(void)
|
|||
|
||||
for (axis = 0; axis < 3; axis++) {
|
||||
uint16_t tmp = min(abs(rcData[axis] - cfg.midrc), 500);
|
||||
#if defined(DEADBAND)
|
||||
if (tmp > DEADBAND) {
|
||||
tmp -= DEADBAND;
|
||||
} else {
|
||||
tmp = 0;
|
||||
if (cfg.deadband > 0) {
|
||||
if (tmp > cfg.deadband) {
|
||||
tmp -= cfg.deadband;
|
||||
} else {
|
||||
tmp = 0;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
if (axis != 2) { //ROLL & PITCH
|
||||
uint16_t tmp2 = tmp / 100;
|
||||
rcCommand[axis] = lookupRX[tmp2] + (tmp - tmp2 * 100) * (lookupRX[tmp2 + 1] - lookupRX[tmp2]) / 100;
|
||||
|
|
1
src/mw.h
1
src/mw.h
|
@ -164,6 +164,7 @@ typedef struct config_t {
|
|||
uint8_t powerTrigger1; // trigger for alarm based on power consumption
|
||||
|
||||
// Radio/ESC-related configuration
|
||||
uint8_t deadband; // introduce a deadband around the stick center. Must be greater than zero
|
||||
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
|
||||
uint16_t minthrottle; // Set the minimum throttle command sent to the ESC (Electronic Speed Controller). This is the minimum value that allow motors to run at a idle speed.
|
||||
uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000
|
||||
|
|
Loading…
Reference in New Issue