Skip to content

Commit

Permalink
feat: racetimer osd
Browse files Browse the repository at this point in the history
  • Loading branch information
Jan Jaap authored and Jan Jaap committed Dec 17, 2023
1 parent bc69a92 commit 7fa762a
Show file tree
Hide file tree
Showing 12 changed files with 290 additions and 9 deletions.
1 change: 1 addition & 0 deletions mk/source.mk
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,7 @@ COMMON_SRC = \
flight/failsafe.c \
flight/gps_rescue.c \
fc/gps_lap_timer.c \
fc/racetimer.c \
flight/dyn_notch_filter.c \
flight/imu.c \
flight/mixer.c \
Expand Down
1 change: 1 addition & 0 deletions src/main/cli/settings.c
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@
#include "fc/controlrate_profile.h"
#include "fc/core.h"
#include "fc/gps_lap_timer.h"
#include "fc/racetimer.h"
#include "fc/parameter_names.h"
#include "fc/rc.h"
#include "fc/rc_adjustments.h"
Expand Down
9 changes: 9 additions & 0 deletions src/main/drivers/osd_symbols.h
Original file line number Diff line number Diff line change
Expand Up @@ -143,6 +143,15 @@
#define SYM_CHECKERED_FLAG 0x24
#define SYM_PREV_LAP_TIME 0x79

// Race Timer
// TODO: figure out how this works and set correct value
#define SYM_RACETIMER_LAST_LAP_TIME 0x77
#define SYM_RACETIMER_BEST_LAP_TIME 0x77
#define SYM_RACETIMER_LAST_GAP_TIME 0x77
#define SYM_RACETIMER_LAP_COUNT 0x77
#define SYM_RACETIMER_CURRENT_POSITION 0x77
#define SYM_RACETIMER_NOTIFICATION 0x77

// Speed
#define SYM_SPEED 0x70
#define SYM_KPH 0x9E
Expand Down
4 changes: 4 additions & 0 deletions src/main/fc/init.c
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,7 @@
#include "fc/board_info.h"
#include "fc/dispatch.h"
#include "fc/gps_lap_timer.h"
#include "fc/racetimer.h"
#include "fc/init.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
Expand Down Expand Up @@ -767,6 +768,9 @@ void init(void)
#ifdef USE_GPS_LAP_TIMER
gpsLapTimerInit();
#endif // USE_GPS_LAP_TIMER
#ifdef USE_RACETIMER
racetimerInit();
#endif // USE_RACETIMER
}
#endif

Expand Down
35 changes: 35 additions & 0 deletions src/main/fc/racetimer.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
/*
* This file is part of Betaflight.
*
* Betaflight is free software. You can redistribute this software
* and/or modify this software under the terms of the GNU General
* Public License as published by the Free Software Foundation,
* either version 3 of the License, or (at your option) any later
* version.
*
* Betaflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
*
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public
* License along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/

#include "racetimer.h"

racetimerData_t racetimerData;

void racetimerOSDInit(void)
{
racetimerData.enabled = false;
racetimerData.lastLapTime = 0;
racetimerData.bestLapTime = 0;
racetimerData.lastGapTime = 0;
racetimerData.lapCount = 0;
racetimerData.currentPosition = 0;
racetimerData.notification[0] = '\0';
}
38 changes: 38 additions & 0 deletions src/main/fc/racetimer.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
/*
* This file is part of Betaflight.
*
* Betaflight is free software. You can redistribute this software
* and/or modify this software under the terms of the GNU General
* Public License as published by the Free Software Foundation,
* either version 3 of the License, or (at your option) any later
* version.
*
* Betaflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
*
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public
* License along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/

#pragma once

#include <stdint.h>

typedef struct racetimerOSDData_s {
bool enabled;
uint32_t lastLapTime;
uint32_t bestLapTime;
uint32_t lastGapTime;
uint16_t lapCount;
uint8_t currentPosition;
char notification[16];
} racetimerData_t;

extern gpsLapTimerData_t racetimerData;

void racetimerOSDInit(void);
92 changes: 92 additions & 0 deletions src/main/msp/msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,7 @@
#include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h"
#include "fc/racetimer.h"

#include "flight/failsafe.h"
#include "flight/gps_rescue.h"
Expand Down Expand Up @@ -2598,6 +2599,97 @@ static mspResult_e mspFcProcessOutCommandWithArg(mspDescriptor_t srcDesc, int16_
break;
#endif

#ifdef USE_RACETIMER
case MSP2_RACETIMER_SET_ENABLE: {
// set racetimerData.enable as boolean
uint8_t value = sbufReadU8(src);
if (value > 1) {
return MSP_RESULT_ERROR;
}

racetimerData.enable = value == 1;
break;
}

case MSP2_RACETIMER_GET_ENABLE: {
// get racetimerData.enable as boolean
sbufWriteU8(dst, racetimerData.enable ? 1 : 0);
break;
}

case MSP2_RACETIMER_SET_LAST_LAP_TIME: {
// set racetimerData.lastLapTime as uint32_t
racetimerData.lastLapTime = sbufReadU32(src);
break;
}

case MSP2_RACETIMER_GET_LAST_LAP_TIME: {
// get racetimerData.lastLapTime as uint32_t
sbufWriteU32(dst, racetimerData.lastLapTime);
break;
}

case MSP2_RACETIMER_SET_BEST_LAP_TIME: {
// set racetimerData.bestLapTime as uint32_t
racetimerData.bestLapTime = sbufReadU32(src);
break;
}

case MSP2_RACETIMER_GET_BEST_LAP_TIME: {
// get racetimerData.bestLapTime as uint32_t
sbufWriteU32(dst, racetimerData.bestLapTime);
break;
}

case MSP2_RACETIMER_SET_LAST_GAP_TIME: {
// set racetimerData.lastGapTime as uint32_t
racetimerData.lastGapTime = sbufReadU32(src);
break;
}

case MSP2_RACETIMER_GET_LAST_GAP_TIME: {
// get racetimerData.lastGapTime as uint32_t
sbufWriteU32(dst, racetimerData.lastGapTime);
break;
}

case MSP2_RACETIMER_SET_LAP_COUNT: {
// set racetimerData.lapCount as uint8_t
racetimerData.lapCount = sbufReadU8(src);
break;
}

case MSP2_RACETIMER_GET_LAP_COUNT: {
// get racetimerData.lapCount as uint8_t
sbufWriteU8(dst, racetimerData.lapCount);
break;
}

case MSP2_RACETIMER_SET_CURRENT_POSITION: {
// set racetimerData.currentPosition as uint8_t
racetimerData.currentPosition = sbufReadU8(src);
break;
}

case MSP2_RACETIMER_GET_CURRENT_POSITION: {
// get racetimerData.currentPosition as uint8_t
sbufWriteU8(dst, racetimerData.currentPosition);
break;
}

case MSP2_RACETIMER_SET_NOTIFICATION: {
// set racetimerData.notification as char[16]
sbufRead(dst, racetimerData.notification, 16);
break;
}

case MSP2_RACETIMER_GET_NOTIFICATION: {
// get racetimerData.notification as char[16]
sbufWrite(dst, racetimerData.notification, 16);
break;
}
#endif

default:
return MSP_RESULT_CMD_UNKNOWN;
}
Expand Down
16 changes: 16 additions & 0 deletions src/main/msp/msp_protocol_v2_betaflight.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,3 +37,19 @@
#define MSP2TEXT_RATE_PROFILE_NAME 4
#define MSP2TEXT_BUILDKEY 5
#define MSP2TEXT_RELEASENAME 6

// RACETIMER
#define MSP2_RACETIMER_SET_ENABLE 0x4000
#define MSP2_RACETIMER_GET_ENABLE 0x4001
#define MSP2_RACETIMER_SET_LAST_LAP_TIME 0x4002
#define MSP2_RACETIMER_GET_LAST_LAP_TIME 0x4003
#define MSP2_RACETIMER_SET_BEST_LAP_TIME 0x4004
#define MSP2_RACETIMER_GET_BEST_LAP_TIME 0x4005
#define MSP2_RACETIMER_SET_LAST_GAP_TIME 0x4006
#define MSP2_RACETIMER_GET_LAST_GAP_TIME 0x4007
#define MSP2_RACETIMER_SET_LAP_COUNT 0x4008
#define MSP2_RACETIMER_GET_LAP_COUNT 0x4009
#define MSP2_RACETIMER_SET_CURRENT_POSITION 0x400A
#define MSP2_RACETIMER_GET_CURRENT_POSITION 0x400B
#define MSP2_RACETIMER_SET_NOTIFICATION 0x400C
#define MSP2_RACETIMER_GET_NOTIFICATION 0x400D
21 changes: 19 additions & 2 deletions src/main/osd/osd.c
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,7 @@

#include "fc/core.h"
#include "fc/gps_lap_timer.h"
#include "fc/racetimer_osd.h"
#include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h"
Expand Down Expand Up @@ -197,6 +198,8 @@ const osd_stats_e osdStatsDisplayOrder[OSD_STAT_COUNT] = {
OSD_STAT_WATT_HOURS_DRAWN,
OSD_STAT_BEST_3_CONSEC_LAPS,
OSD_STAT_BEST_LAP,
OSD_STAT_RACETIMER_FASTEST_LAPTIME,
OSD_STAT_RACETIMER_LAP_COUNT,
OSD_STAT_FULL_THROTTLE_TIME,
OSD_STAT_FULL_THROTTLE_COUNTER,
OSD_STAT_AVG_THROTTLE,
Expand Down Expand Up @@ -571,7 +574,7 @@ void osdInit(displayPort_t *osdDisplayPortToUse, osdDisplayPortDevice_e displayP
}
}

#ifdef USE_GPS_LAP_TIMER
#ifdef USE_RACETIMER
void printLapTime(char *buffer, const uint32_t timeMs) {
if (timeMs != 0) {
const uint32_t timeRoundMs = timeMs + 5; // round value in division by 10
Expand All @@ -582,7 +585,7 @@ void printLapTime(char *buffer, const uint32_t timeMs) {
tfp_sprintf(buffer, " -.--");
}
}
#endif // USE_GPS_LAP_TIMER
#endif // USE_RACETIMER

static void osdResetStats(void)
{
Expand Down Expand Up @@ -1004,6 +1007,20 @@ static bool osdDisplayStat(int statistic, uint8_t displayRow)
}
#endif // USE_GPS_LAP_TIMER

#ifdef USE_RACETIMER
case OSD_STAT_RACETIMER_FASTEST_LAPTIME: {
printLapTime(buff, raceTimerData.fastestLapTime);
osdDisplayStatisticLabel(midCol, displayRow, "FASTEST LAP", buff);
return true;
}

case OSD_STAT_RACETIMER_LAP_COUNT: {
itoa(raceTimerData.lapCount, buff, 10);
osdDisplayStatisticLabel(midCol, displayRow, "LAP COUNT", buff);
return true;
}
#endif

#ifdef USE_PERSISTENT_STATS
case OSD_STAT_TOTAL_FLIGHTS:
itoa(statsConfig()->stats_total_flights, buff, 10);
Expand Down
6 changes: 6 additions & 0 deletions src/main/osd/osd.h
Original file line number Diff line number Diff line change
Expand Up @@ -189,6 +189,12 @@ typedef enum {
OSD_GPS_LAP_TIME_CURRENT,
OSD_GPS_LAP_TIME_PREVIOUS,
OSD_GPS_LAP_TIME_BEST3,
OSD_RACETIMER_LAST_LAP_TIME,
OSD_RACETIMER_BEST_LAP_TIME,
OSD_RACETIMER_LAST_GAPT_TIME,
OSD_RACETIMER_LAP_COUNT,
OSD_RACETIMER_CURRENT_POSITION,
OSD_RACETIMER_NOTIFICATION,
OSD_ITEM_COUNT // MUST BE LAST
} osd_items_e;

Expand Down
Loading

0 comments on commit 7fa762a

Please sign in to comment.