Skip to content

Commit

Permalink
Bump to share (ExpressLRS#1510)
Browse files Browse the repository at this point in the history
* bump/tap detection on accelerometer

* Log the g-sensor data at the end of bumping

Add float logging

* Allow single bump transfer if the radio is in the upright position

* Move deferred function calling to rxtx_common

* STM32 has no room left when debugging

* Changes as per review

* More cleanup as per review

* Tie the bump-to-share function to having motion detection enabled

* Don't do bump loan/bind if armed!
  • Loading branch information
pkendall64 authored and bkleiner committed Jun 12, 2022
1 parent a98a9c5 commit abca25b
Show file tree
Hide file tree
Showing 13 changed files with 161 additions and 73 deletions.
1 change: 1 addition & 0 deletions src/include/rxtx_common.h
Expand Up @@ -14,3 +14,4 @@
#include "POWERMGNT.h"

void setupTargetCommon();
void executeDeferredFunction(unsigned long now);
78 changes: 62 additions & 16 deletions src/lib/GSENSOR/devGsensor.cpp
Expand Up @@ -7,9 +7,12 @@
#define OPT_HAS_GSENSOR true
#endif

#include <functional>

#include "gsensor.h"
#include "POWERMGNT.h"
#include "config.h"
#include "logging.h"

#if defined(TARGET_TX)
extern TxConfig config;
Expand All @@ -19,12 +22,22 @@ extern RxConfig config;

Gsensor gsensor;

int system_quiet_state = GSENSOR_SYSTEM_STATE_MOVING;
int system_quiet_pre_state = GSENSOR_SYSTEM_STATE_MOVING;
static int system_quiet_state = GSENSOR_SYSTEM_STATE_MOVING;
static int system_quiet_pre_state = GSENSOR_SYSTEM_STATE_MOVING;
static unsigned int bumps = 0;
static unsigned long lastBumpTime = 0;
static unsigned long lastBumpCommand = 0;

extern bool IsArmed();
extern void SendRxLoanOverMSP();
extern void EnterBindingMode();
extern void deferExecution(uint32_t ms, std::function<void()> f);

extern bool ICACHE_RAM_ATTR IsArmed();
#define GSENSOR_DURATION 10
#define GSENSOR_SYSTEM_IDLE_INTERVAL 1000U

#define GSENSOR_DURATION 1000
#define MULTIPLE_BUMP_INTERVAL 400U
#define BUMP_COMMAND_IDLE_TIME 10000U

static void initialize()
{
Expand All @@ -45,23 +58,56 @@ static int start()

static int timeout()
{
gsensor.handle();

system_quiet_state = gsensor.getSystemState();
//When system is idle, set power to minimum
if(config.GetMotionMode() == 1)
static unsigned long lastIdleCheckMs = 0;
unsigned long now = millis();
if (config.GetMotionMode() == 1 && gsensor.hasTriggered(now) && (now - lastBumpCommand) > BUMP_COMMAND_IDLE_TIME)
{
lastBumpTime = now;
bumps++;
}
if (bumps > 0 && (now - lastBumpTime > MULTIPLE_BUMP_INTERVAL))
{
if((system_quiet_state == GSENSOR_SYSTEM_STATE_QUIET) && (system_quiet_pre_state == GSENSOR_SYSTEM_STATE_MOVING) && !IsArmed())
float x, y, z;
gsensor.getGSensorData(&x, &y, &z);
// Single bump while holding the radio antenna up and NOT armed is Loan/Bind
if (!IsArmed() && bumps == 1 && fabs(x) < 0.5 && y < -0.8 && fabs(z) < 0.5)
{
POWERMGNT::setPower(MinPower);
lastBumpCommand = now;
if (connectionState == connected)
{
DBGLN("Loaning model");
SendRxLoanOverMSP();
}
else
{
DBGLN("Borrowing model");
// defer this calling `EnterBindingMode` for 2 seconds
deferExecution(2000, EnterBindingMode);
}
}
if((system_quiet_state == GSENSOR_SYSTEM_STATE_MOVING) && (system_quiet_pre_state == GSENSOR_SYSTEM_STATE_QUIET))
DBGLN("Bumps %d : %f %f %f", bumps, x, y, z);
bumps = 0;
}
if (now - lastIdleCheckMs > GSENSOR_SYSTEM_IDLE_INTERVAL)
{
gsensor.handle();

system_quiet_state = gsensor.getSystemState();
//When system is idle, set power to minimum
if(config.GetMotionMode() == 1)
{
POWERMGNT::setPower((PowerLevels_e)config.GetPower());
if((system_quiet_state == GSENSOR_SYSTEM_STATE_QUIET) && (system_quiet_pre_state == GSENSOR_SYSTEM_STATE_MOVING) && !IsArmed())
{
POWERMGNT::setPower(MinPower);
}
if((system_quiet_state == GSENSOR_SYSTEM_STATE_MOVING) && (system_quiet_pre_state == GSENSOR_SYSTEM_STATE_QUIET))
{
POWERMGNT::setPower((PowerLevels_e)config.GetPower());
}
}
system_quiet_pre_state = system_quiet_state;
lastIdleCheckMs = now;
}
system_quiet_pre_state = system_quiet_state;

return GSENSOR_DURATION;
}

Expand All @@ -72,4 +118,4 @@ device_t Gsensor_device = {
.timeout = timeout
};

#endif
#endif
46 changes: 24 additions & 22 deletions src/lib/GSENSOR/gsensor.cpp
Expand Up @@ -28,16 +28,17 @@ float x_average = 0;
float y_average = 0;
float z_average = 0;

static int motion_event_counter = 0;
static bool interrupt = false;

#ifdef HAS_SMART_FAN
extern bool is_smart_fan_control;
uint32_t smart_fan_start_time = 0;
#define SMART_FAN_TIME_OUT 5000
#endif

ICACHE_RAM_ATTR void handleGsensorInterrupt() {
motion_event_counter++;
ICACHE_RAM_ATTR void handleGsensorInterrupt()
{
interrupt = true;
}

void Gsensor::init()
Expand Down Expand Up @@ -96,12 +97,26 @@ float get_data_variance(float average, float *data, int length)
return variance;
}

bool Gsensor::hasTriggered(unsigned long now)
{
static unsigned long lastTriggeredMs = 0;

if (interrupt)
{
interrupt = false;
if (now - lastTriggeredMs > 20)
{
lastTriggeredMs = now;
return true;
}
}
return false;
}

void Gsensor::handle()
{
bool data_check_quiet = false;

float x, y, z;

getGSensorData(&x, &y, &z);
#ifdef HAS_SMART_FAN
if(z < -0.5f)
Expand All @@ -125,7 +140,8 @@ void Gsensor::handle()
{
is_flipped = false;
}
if(system_state == GSENSOR_SYSTEM_STATE_QUIET){
if(system_state == GSENSOR_SYSTEM_STATE_QUIET)
{
x = abs(x - x_average);
y = abs(y - y_average);
z = abs(z - z_average);
Expand All @@ -152,30 +168,16 @@ void Gsensor::handle()
float y_variance = get_data_variance(y_average, y_buffer, DATA_SAMPLE_LENGTH);
float z_variance = get_data_variance(z_average, z_buffer, DATA_SAMPLE_LENGTH);

if((x_variance < QUIET_VARIANCE_THRESHOLD) & (y_variance < QUIET_VARIANCE_THRESHOLD) &
if((x_variance < QUIET_VARIANCE_THRESHOLD) && (y_variance < QUIET_VARIANCE_THRESHOLD) &&
(z_variance < QUIET_VARIANCE_THRESHOLD))
{
data_check_quiet = true;
system_state = GSENSOR_SYSTEM_STATE_QUIET;
}

}
else
{
sample_counter++;
}

if(motion_event_counter !=0)
{
system_state = GSENSOR_SYSTEM_STATE_MOVING;
motion_event_counter = 0;
}else if(data_check_quiet)
{
system_state = GSENSOR_SYSTEM_STATE_QUIET;
}
else
{
system_state = GSENSOR_SYSTEM_STATE_MOVING;
}
}
}

Expand Down
5 changes: 1 addition & 4 deletions src/lib/GSENSOR/gsensor.h
Expand Up @@ -23,11 +23,8 @@ class Gsensor
public:
void init();
void handle();
bool hasTriggered(unsigned long now);
void getGSensorData(float *X_DataOut, float *Y_DataOut, float *Z_DataOut);
int getSystemState();
bool isFlipped();

};



2 changes: 1 addition & 1 deletion src/lib/GSENSOR/stk8baxx.h
Expand Up @@ -79,7 +79,7 @@ class STK8xxx
#define STK8xxx_VAL_INT_OD bit(1)

#define STK8xxx_REG_SLOPETHD 0x28
#define STK8xxx_VAL_SLP_DFLT 0x14
#define STK8xxx_VAL_SLP_DFLT 150 // 0x14

#define STK8xxx_REG_SIGMOT2 0x2A
#define STK8xxx_VAL_SKIP_TIME bit(0)
Expand Down
16 changes: 0 additions & 16 deletions src/lib/LUA/lua.cpp
Expand Up @@ -29,10 +29,6 @@ static luaCallback paramCallbacks[LUA_MAX_PARAMS] = {0};
static uint8_t lastLuaField = 0;
static uint8_t nextStatusChunk = 0;

static uint32_t startDeferredTime = 0;
static uint32_t deferredTimeout = 0;
static std::function<void()> deferredFunction = nullptr;

static uint8_t luaSelectionOptionMax(const char *strOptions)
{
// Returns the max index of the semicolon-delimited option string
Expand Down Expand Up @@ -344,20 +340,8 @@ void registerLUAParameter(void *definition, luaCallback callback, uint8_t parent
paramCallbacks[lastLuaField] = callback;
}

void deferExecution(uint32_t ms, std::function<void()> f)
{
startDeferredTime = millis();
deferredTimeout = ms;
deferredFunction = f;
}

bool luaHandleUpdateParameter()
{
if (deferredFunction!=nullptr && (millis() - startDeferredTime) > deferredTimeout)
{
deferredFunction();
deferredFunction = nullptr;
}
if (UpdateParamReq == false)
{
return false;
Expand Down
1 change: 0 additions & 1 deletion src/lib/LUA/lua.h
Expand Up @@ -126,7 +126,6 @@ void sendLuaCommandResponse(struct luaItem_command *cmd, luaCmdStep_e step, cons

extern void ICACHE_RAM_ATTR luaParamUpdateReq();
extern bool luaHandleUpdateParameter();
extern void deferExecution(uint32_t ms, std::function<void()> f);

typedef void (*luaCallback)(struct luaPropertiesCommon *item, uint8_t arg);
void registerLUAParameter(void *definition, luaCallback callback = nullptr, uint8_t parent = 0);
Expand Down
2 changes: 2 additions & 0 deletions src/lib/LUA/rx_devLUA.cpp
Expand Up @@ -12,6 +12,8 @@
#include "hwTimer.h"
#include "FHSS.h"

extern void deferExecution(uint32_t ms, std::function<void()> f);

extern bool InLoanBindingMode;
extern bool returnModelFromLoan;

Expand Down
1 change: 1 addition & 0 deletions src/lib/MSP/msptypes.h
Expand Up @@ -17,6 +17,7 @@
#define MSP_ELRS_SET_TX_BACKPACK_WIFI_MODE 0x0C
#define MSP_ELRS_SET_VRX_BACKPACK_WIFI_MODE 0x0D
#define MSP_ELRS_SET_RX_WIFI_MODE 0x0E
#define MSP_ELRS_SET_RX_LOAN_MODE 0x0F

#define MSP_ELRS_POWER_CALI_GET 0x20
#define MSP_ELRS_POWER_CALI_SET 0x21
Expand Down
13 changes: 12 additions & 1 deletion src/lib/logging/logging.cpp
Expand Up @@ -12,7 +12,7 @@ void debugPrintf(const char* fmt, ...)
{
char c;
const char *v;
char buf[11];
char buf[21];
va_list vlist;
va_start(vlist,fmt);

Expand All @@ -36,6 +36,17 @@ void debugPrintf(const char* fmt, ...)
case 'x':
utoa(va_arg(vlist, uint32_t), buf, HEX);
break;
#if !defined(PLATFORM_STM32)
case 'f':
{
float val = va_arg(vlist, double);
itoa((int32_t)val, buf, DEC);
strcat(buf, ".");
int32_t decimals = abs((int32_t)(val * 1000)) % 1000;
itoa(decimals, buf + strlen(buf), DEC);
}
break;
#endif
default:
break;
}
Expand Down

0 comments on commit abca25b

Please sign in to comment.