1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-17 13:25:30 +03:00

Updated accgyro locking. Printf tidy

This commit is contained in:
Martin Budden 2017-04-10 14:34:21 +01:00
parent 8eebf06753
commit 0219d6adc7
13 changed files with 109 additions and 107 deletions

View file

@ -113,9 +113,6 @@ int tfp_sprintf(char *s, const char *fmt, ...);
int tfp_format(void *putp, void (*putf) (void *, char), const char *fmt, va_list va); int tfp_format(void *putp, void (*putf) (void *, char), const char *fmt, va_list va);
#define printf tfp_printf
#define sprintf tfp_sprintf
struct serialPort_s; struct serialPort_s;
void setPrintfSerialPort(struct serialPort_s *serialPort); void setPrintfSerialPort(struct serialPort_s *serialPort);
void printfSupportInit(void); void printfSupportInit(void);

View file

@ -17,10 +17,14 @@
#pragma once #pragma once
#include "platform.h"
#include "common/axis.h" #include "common/axis.h"
#include "drivers/exti.h" #include "drivers/exti.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/accgyro_mpu.h" #include "drivers/accgyro_mpu.h"
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD)
#include <pthread.h>
#endif
#ifndef MPU_I2C_INSTANCE #ifndef MPU_I2C_INSTANCE
#define MPU_I2C_INSTANCE I2C_DEVICE #define MPU_I2C_INSTANCE I2C_DEVICE
@ -58,6 +62,9 @@ typedef struct gyroDev_s {
gyroRateKHz_e gyroRateKHz; gyroRateKHz_e gyroRateKHz;
uint8_t mpuDividerDrops; uint8_t mpuDividerDrops;
bool dataReady; bool dataReady;
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD)
pthread_mutex_t lock;
#endif
sensor_align_e gyroAlign; sensor_align_e gyroAlign;
mpuDetectionResult_t mpuDetectionResult; mpuDetectionResult_t mpuDetectionResult;
const extiConfig_t *mpuIntExtiConfig; const extiConfig_t *mpuIntExtiConfig;
@ -72,7 +79,46 @@ typedef struct accDev_s {
int16_t ADCRaw[XYZ_AXIS_COUNT]; int16_t ADCRaw[XYZ_AXIS_COUNT];
char revisionCode; // a revision code for the sensor, if known char revisionCode; // a revision code for the sensor, if known
bool dataReady; bool dataReady;
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD)
pthread_mutex_t lock;
#endif
sensor_align_e accAlign; sensor_align_e accAlign;
mpuDetectionResult_t mpuDetectionResult; mpuDetectionResult_t mpuDetectionResult;
mpuConfiguration_t mpuConfiguration; mpuConfiguration_t mpuConfiguration;
} accDev_t; } accDev_t;
static inline void accDevLock(accDev_t *acc)
{
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD)
pthread_mutex_lock(&acc->lock);
#else
(void)acc;
#endif
}
static inline void accDevUnLock(accDev_t *acc)
{
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD)
pthread_mutex_unlock(&acc->lock);
#else
(void)acc;
#endif
}
static inline void gyroDevLock(gyroDev_t *gyro)
{
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD)
pthread_mutex_lock(&gyro->lock);
#else
(void)gyro;
#endif
}
static inline void gyroDevUnLock(gyroDev_t *gyro)
{
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD)
pthread_mutex_unlock(&gyro->lock);
#else
(void)gyro;
#endif
}

View file

@ -36,39 +36,19 @@
static int16_t fakeGyroADC[XYZ_AXIS_COUNT]; static int16_t fakeGyroADC[XYZ_AXIS_COUNT];
gyroDev_t *fakeGyroDev; gyroDev_t *fakeGyroDev;
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD)
static pthread_mutex_t gyroLock;
#endif
static void fakeGyroInit(gyroDev_t *gyro) static void fakeGyroInit(gyroDev_t *gyro)
{ {
fakeGyroDev = gyro; fakeGyroDev = gyro;
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD) #if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD)
if (pthread_mutex_init(&gyroLock, NULL) != 0) { if (pthread_mutex_init(&gyro->lock, NULL) != 0) {
printf("Create gyroLock error!\n"); printf("Create gyro lock error!\n");
} }
#endif #endif
} }
static void fakeGyroLock(gyroDev_t *gyro)
{
UNUSED(gyro);
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD)
pthread_mutex_lock(&gyroLock);
#endif
}
static void fakeGyroUnLock(gyroDev_t *gyro)
{
UNUSED(gyro);
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD)
pthread_mutex_unlock(&gyroLock);
#endif
}
void fakeGyroSet(gyroDev_t *gyro, int16_t x, int16_t y, int16_t z) void fakeGyroSet(gyroDev_t *gyro, int16_t x, int16_t y, int16_t z)
{ {
fakeGyroLock(gyro); gyroDevLock(gyro);
fakeGyroADC[X] = x; fakeGyroADC[X] = x;
fakeGyroADC[Y] = y; fakeGyroADC[Y] = y;
@ -76,14 +56,14 @@ void fakeGyroSet(gyroDev_t *gyro, int16_t x, int16_t y, int16_t z)
gyro->dataReady = true; gyro->dataReady = true;
fakeGyroUnLock(gyro); gyroDevUnLock(gyro);
} }
static bool fakeGyroRead(gyroDev_t *gyro) static bool fakeGyroRead(gyroDev_t *gyro)
{ {
fakeGyroLock(gyro); gyroDevLock(gyro);
if (gyro->dataReady == false) { if (gyro->dataReady == false) {
fakeGyroUnLock(gyro); gyroDevUnLock(gyro);
return false; return false;
} }
gyro->dataReady = false; gyro->dataReady = false;
@ -92,7 +72,7 @@ static bool fakeGyroRead(gyroDev_t *gyro)
gyro->gyroADCRaw[Y] = fakeGyroADC[Y]; gyro->gyroADCRaw[Y] = fakeGyroADC[Y];
gyro->gyroADCRaw[Z] = fakeGyroADC[Z]; gyro->gyroADCRaw[Z] = fakeGyroADC[Z];
fakeGyroUnLock(gyro); gyroDevUnLock(gyro);
return true; return true;
} }
@ -130,39 +110,19 @@ bool fakeGyroDetect(gyroDev_t *gyro)
static int16_t fakeAccData[XYZ_AXIS_COUNT]; static int16_t fakeAccData[XYZ_AXIS_COUNT];
accDev_t *fakeAccDev; accDev_t *fakeAccDev;
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD)
static pthread_mutex_t accLock;
#endif
static void fakeAccInit(accDev_t *acc) static void fakeAccInit(accDev_t *acc)
{ {
fakeAccDev = acc; fakeAccDev = acc;
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD) #if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD)
if (pthread_mutex_init(&accLock, NULL) != 0) { if (pthread_mutex_init(&acc->lock, NULL) != 0) {
printf("Create accLock error!\n"); printf("Create acc lock error!\n");
} }
#endif #endif
} }
static void fakeAccLock(accDev_t *acc)
{
UNUSED(acc);
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD)
pthread_mutex_lock(&accLock);
#endif
}
static void fakeAccUnLock(accDev_t *acc)
{
UNUSED(acc);
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD)
pthread_mutex_unlock(&accLock);
#endif
}
void fakeAccSet(accDev_t *acc, int16_t x, int16_t y, int16_t z) void fakeAccSet(accDev_t *acc, int16_t x, int16_t y, int16_t z)
{ {
fakeAccLock(acc); accDevLock(acc);
fakeAccData[X] = x; fakeAccData[X] = x;
fakeAccData[Y] = y; fakeAccData[Y] = y;
@ -170,14 +130,14 @@ void fakeAccSet(accDev_t *acc, int16_t x, int16_t y, int16_t z)
acc->dataReady = true; acc->dataReady = true;
fakeAccUnLock(acc); accDevUnLock(acc);
} }
static bool fakeAccRead(accDev_t *acc) static bool fakeAccRead(accDev_t *acc)
{ {
fakeAccLock(acc); accDevLock(acc);
if (acc->dataReady == false) { if (acc->dataReady == false) {
fakeAccUnLock(acc); accDevUnLock(acc);
return false; return false;
} }
acc->dataReady = false; acc->dataReady = false;
@ -186,7 +146,7 @@ static bool fakeAccRead(accDev_t *acc)
acc->ADCRaw[Y] = fakeAccData[Y]; acc->ADCRaw[Y] = fakeAccData[Y];
acc->ADCRaw[Z] = fakeAccData[Z]; acc->ADCRaw[Z] = fakeAccData[Z];
fakeAccUnLock(acc); accDevUnLock(acc);
return true; return true;
} }

View file

@ -15,14 +15,14 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>. * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include "platform.h"
#include "io.h" #include "io.h"
#include "io_impl.h" #include "io_impl.h"
#include "rcc.h" #include "rcc.h"
#include "common/utils.h" #include "common/utils.h"
#include "target.h"
// io ports defs are stored in array by index now // io ports defs are stored in array by index now
struct ioPortDef_s { struct ioPortDef_s {
rccPeriphTag_t rcc; rccPeriphTag_t rcc;

View file

@ -21,6 +21,7 @@
#include <stdint.h> #include <stdint.h>
#include <platform.h> #include <platform.h>
#include "resource.h" #include "resource.h"
#include "io_types.h" #include "io_types.h"

View file

@ -18,9 +18,10 @@
#pragma once #pragma once
// TODO - GPIO_TypeDef include // TODO - GPIO_TypeDef include
#include "io.h"
#include "platform.h" #include "platform.h"
#include "io.h"
typedef struct ioDef_s { typedef struct ioDef_s {
ioTag_t tag; ioTag_t tag;
} ioDef_t; } ioDef_t;

View file

@ -1908,12 +1908,12 @@ static void cliSerialPassthrough(char *cmdline)
tok = strtok_r(NULL, " ", &saveptr); tok = strtok_r(NULL, " ", &saveptr);
} }
printf("Port %d ", id); tfp_printf("Port %d ", id);
serialPort_t *passThroughPort; serialPort_t *passThroughPort;
serialPortUsage_t *passThroughPortUsage = findSerialPortUsageByIdentifier(id); serialPortUsage_t *passThroughPortUsage = findSerialPortUsageByIdentifier(id);
if (!passThroughPortUsage || passThroughPortUsage->serialPort == NULL) { if (!passThroughPortUsage || passThroughPortUsage->serialPort == NULL) {
if (!baud) { if (!baud) {
printf("closed, specify baud.\r\n"); tfp_printf("closed, specify baud.\r\n");
return; return;
} }
if (!mode) if (!mode)
@ -1923,17 +1923,17 @@ static void cliSerialPassthrough(char *cmdline)
baud, mode, baud, mode,
SERIAL_NOT_INVERTED); SERIAL_NOT_INVERTED);
if (!passThroughPort) { if (!passThroughPort) {
printf("could not be opened.\r\n"); tfp_printf("could not be opened.\r\n");
return; return;
} }
printf("opened, baud = %d.\r\n", baud); tfp_printf("opened, baud = %d.\r\n", baud);
} else { } else {
passThroughPort = passThroughPortUsage->serialPort; passThroughPort = passThroughPortUsage->serialPort;
// If the user supplied a mode, override the port's mode, otherwise // If the user supplied a mode, override the port's mode, otherwise
// leave the mode unchanged. serialPassthrough() handles one-way ports. // leave the mode unchanged. serialPassthrough() handles one-way ports.
printf("already open.\r\n"); tfp_printf("already open.\r\n");
if (mode && passThroughPort->mode != mode) { if (mode && passThroughPort->mode != mode) {
printf("mode changed from %d to %d.\r\n", tfp_printf("mode changed from %d to %d.\r\n",
passThroughPort->mode, mode); passThroughPort->mode, mode);
serialSetMode(passThroughPort, mode); serialSetMode(passThroughPort, mode);
} }
@ -1944,7 +1944,7 @@ static void cliSerialPassthrough(char *cmdline)
} }
} }
printf("forwarding, power cycle to exit.\r\n"); tfp_printf("forwarding, power cycle to exit.\r\n");
serialPassthrough(cliPort, passThroughPort, NULL, NULL); serialPassthrough(cliPort, passThroughPort, NULL, NULL);
} }
@ -3227,11 +3227,11 @@ static void cliGpsPassthrough(char *cmdline)
static int parseEscNumber(char *pch, bool allowAllEscs) { static int parseEscNumber(char *pch, bool allowAllEscs) {
int escNumber = atoi(pch); int escNumber = atoi(pch);
if ((escNumber >= 0) && (escNumber < getMotorCount())) { if ((escNumber >= 0) && (escNumber < getMotorCount())) {
printf("Programming on ESC %d.\r\n", escNumber); tfp_printf("Programming on ESC %d.\r\n", escNumber);
} else if (allowAllEscs && escNumber == ALL_ESCS) { } else if (allowAllEscs && escNumber == ALL_ESCS) {
printf("Programming on all ESCs.\r\n"); tfp_printf("Programming on all ESCs.\r\n");
} else { } else {
printf("Invalid ESC number, range: 0 to %d.\r\n", getMotorCount() - 1); tfp_printf("Invalid ESC number, range: 0 to %d.\r\n", getMotorCount() - 1);
return -1; return -1;
} }
@ -3279,9 +3279,9 @@ static void cliDshotProg(char *cmdline)
delay(10); // wait for sound output to finish delay(10); // wait for sound output to finish
} }
printf("Command %d written.\r\n", command); tfp_printf("Command %d written.\r\n", command);
} else { } else {
printf("Invalid command, range 1 to %d.\r\n", DSHOT_MIN_THROTTLE - 1); tfp_printf("Invalid command, range 1 to %d.\r\n", DSHOT_MIN_THROTTLE - 1);
} }
break; break;
@ -3726,7 +3726,7 @@ static void cliTasks(char *cmdline)
getTaskInfo(taskId, &taskInfo); getTaskInfo(taskId, &taskInfo);
if (taskInfo.isEnabled) { if (taskInfo.isEnabled) {
int taskFrequency; int taskFrequency;
int subTaskFrequency; int subTaskFrequency = 0;
if (taskId == TASK_GYROPID) { if (taskId == TASK_GYROPID) {
subTaskFrequency = taskInfo.latestDeltaTime == 0 ? 0 : (int)(1000000.0f / ((float)taskInfo.latestDeltaTime)); subTaskFrequency = taskInfo.latestDeltaTime == 0 ? 0 : (int)(1000000.0f / ((float)taskInfo.latestDeltaTime));
taskFrequency = subTaskFrequency / pidConfig()->pid_process_denom; taskFrequency = subTaskFrequency / pidConfig()->pid_process_denom;

View file

@ -477,7 +477,7 @@ void processRx(timeUs_t currentTimeUs)
static void subTaskPidController(void) static void subTaskPidController(void)
{ {
uint32_t startTime; uint32_t startTime = 0;
if (debugMode == DEBUG_PIDLOOP) {startTime = micros();} if (debugMode == DEBUG_PIDLOOP) {startTime = micros();}
// PID - note this is function pointer set by setPIDController() // PID - note this is function pointer set by setPIDController()
pidController(currentPidProfile, &accelerometerConfig()->accelerometerTrims); pidController(currentPidProfile, &accelerometerConfig()->accelerometerTrims);
@ -486,7 +486,7 @@ static void subTaskPidController(void)
static void subTaskMainSubprocesses(timeUs_t currentTimeUs) static void subTaskMainSubprocesses(timeUs_t currentTimeUs)
{ {
uint32_t startTime; uint32_t startTime = 0;
if (debugMode == DEBUG_PIDLOOP) {startTime = micros();} if (debugMode == DEBUG_PIDLOOP) {startTime = micros();}
// Read out gyro temperature if used for telemmetry // Read out gyro temperature if used for telemmetry
@ -560,7 +560,7 @@ static void subTaskMainSubprocesses(timeUs_t currentTimeUs)
static void subTaskMotorUpdate(void) static void subTaskMotorUpdate(void)
{ {
uint32_t startTime; uint32_t startTime = 0;
if (debugMode == DEBUG_CYCLETIME) { if (debugMode == DEBUG_CYCLETIME) {
startTime = micros(); startTime = micros();
static uint32_t previousMotorUpdateTime; static uint32_t previousMotorUpdateTime;
@ -621,7 +621,7 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
// 1 - pidController() // 1 - pidController()
// 2 - subTaskMainSubprocesses() // 2 - subTaskMainSubprocesses()
// 3 - subTaskMotorUpdate() // 3 - subTaskMotorUpdate()
uint32_t startTime; uint32_t startTime = 0;
if (debugMode == DEBUG_PIDLOOP) {startTime = micros();} if (debugMode == DEBUG_PIDLOOP) {startTime = micros();}
gyroUpdate(); gyroUpdate();
DEBUG_SET(DEBUG_PIDLOOP, 0, micros() - startTime); DEBUG_SET(DEBUG_PIDLOOP, 0, micros() - startTime);

View file

@ -52,8 +52,6 @@
#if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD) #if defined(SIMULATOR_BUILD) && defined(SIMULATOR_MULTITHREAD)
#include <stdio.h> #include <stdio.h>
#include <pthread.h> #include <pthread.h>
#define printf printf
#define sprintf sprintf
static pthread_mutex_t imuUpdateLock; static pthread_mutex_t imuUpdateLock;

View file

@ -377,7 +377,7 @@ void generateLedConfig(ledConfig_t *ledConfig, char *ledConfigBuffer, size_t buf
*fptr = 0; *fptr = 0;
// TODO - check buffer length // TODO - check buffer length
sprintf(ledConfigBuffer, "%u,%u:%s:%s:%u", ledGetX(ledConfig), ledGetY(ledConfig), directions, baseFunctionOverlays, ledGetColor(ledConfig)); tfp_sprintf(ledConfigBuffer, "%u,%u:%s:%s:%u", ledGetX(ledConfig), ledGetY(ledConfig), directions, baseFunctionOverlays, ledGetColor(ledConfig));
} }
typedef enum { typedef enum {

View file

@ -74,6 +74,7 @@
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "flight/altitude.h"
#include "flight/imu.h" #include "flight/imu.h"
#include "rx/rx.h" #include "rx/rx.h"
@ -188,14 +189,14 @@ static void osdDrawSingleElement(uint8_t item)
osdRssi = 99; osdRssi = 99;
buff[0] = SYM_RSSI; buff[0] = SYM_RSSI;
sprintf(buff + 1, "%d", osdRssi); tfp_sprintf(buff + 1, "%d", osdRssi);
break; break;
} }
case OSD_MAIN_BATT_VOLTAGE: case OSD_MAIN_BATT_VOLTAGE:
{ {
buff[0] = SYM_BATT_5; buff[0] = SYM_BATT_5;
sprintf(buff + 1, "%d.%1dV", getBatteryVoltage() / 10, getBatteryVoltage() % 10); tfp_sprintf(buff + 1, "%d.%1dV", getBatteryVoltage() / 10, getBatteryVoltage() % 10);
break; break;
} }
@ -203,14 +204,14 @@ static void osdDrawSingleElement(uint8_t item)
{ {
int32_t amperage = getAmperage(); int32_t amperage = getAmperage();
buff[0] = SYM_AMP; buff[0] = SYM_AMP;
sprintf(buff + 1, "%d.%02d", abs(amperage) / 100, abs(amperage) % 100); tfp_sprintf(buff + 1, "%d.%02d", abs(amperage) / 100, abs(amperage) % 100);
break; break;
} }
case OSD_MAH_DRAWN: case OSD_MAH_DRAWN:
{ {
buff[0] = SYM_MAH; buff[0] = SYM_MAH;
sprintf(buff + 1, "%d", getMAhDrawn()); tfp_sprintf(buff + 1, "%d", getMAhDrawn());
break; break;
} }
@ -218,14 +219,14 @@ static void osdDrawSingleElement(uint8_t item)
case OSD_GPS_SATS: case OSD_GPS_SATS:
{ {
buff[0] = 0x1f; buff[0] = 0x1f;
sprintf(buff + 1, "%d", GPS_numSat); tfp_sprintf(buff + 1, "%d", GPS_numSat);
break; break;
} }
case OSD_GPS_SPEED: case OSD_GPS_SPEED:
{ {
// FIXME ideally we want to use SYM_KMH symbol but it's not in the font any more, so we use K. // FIXME ideally we want to use SYM_KMH symbol but it's not in the font any more, so we use K.
sprintf(buff, "%dK", CM_S_TO_KM_H(GPS_speed) * 10); tfp_sprintf(buff, "%dK", CM_S_TO_KM_H(GPS_speed) * 10);
break; break;
} }
@ -257,7 +258,7 @@ static void osdDrawSingleElement(uint8_t item)
case OSD_ALTITUDE: case OSD_ALTITUDE:
{ {
int32_t alt = osdGetAltitude(getEstimatedAltitude()); int32_t alt = osdGetAltitude(getEstimatedAltitude());
sprintf(buff, "%c%d.%01d%c", alt < 0 ? '-' : ' ', abs(alt / 100), abs((alt % 100) / 10), osdGetAltitudeSymbol()); tfp_sprintf(buff, "%c%d.%01d%c", alt < 0 ? '-' : ' ', abs(alt / 100), abs((alt % 100) / 10), osdGetAltitudeSymbol());
break; break;
} }
@ -265,14 +266,14 @@ static void osdDrawSingleElement(uint8_t item)
{ {
uint32_t seconds = micros() / 1000000; uint32_t seconds = micros() / 1000000;
buff[0] = SYM_ON_M; buff[0] = SYM_ON_M;
sprintf(buff + 1, "%02d:%02d", seconds / 60, seconds % 60); tfp_sprintf(buff + 1, "%02d:%02d", seconds / 60, seconds % 60);
break; break;
} }
case OSD_FLYTIME: case OSD_FLYTIME:
{ {
buff[0] = SYM_FLY_M; buff[0] = SYM_FLY_M;
sprintf(buff + 1, "%02d:%02d", flyTime / 60, flyTime % 60); tfp_sprintf(buff + 1, "%02d:%02d", flyTime / 60, flyTime % 60);
break; break;
} }
@ -313,7 +314,7 @@ static void osdDrawSingleElement(uint8_t item)
{ {
buff[0] = SYM_THR; buff[0] = SYM_THR;
buff[1] = SYM_THR1; buff[1] = SYM_THR1;
sprintf(buff + 2, "%d", (constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN)); tfp_sprintf(buff + 2, "%d", (constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN));
break; break;
} }
@ -324,9 +325,9 @@ static void osdDrawSingleElement(uint8_t item)
#if defined(VTX) #if defined(VTX)
const char vtxBandLetter = vtx58BandLetter[vtxConfig()->vtx_band + 1]; const char vtxBandLetter = vtx58BandLetter[vtxConfig()->vtx_band + 1];
const char *vtxChannelName = vtx58ChannelNames[vtxConfig()->vtx_channel + 1]; const char *vtxChannelName = vtx58ChannelNames[vtxConfig()->vtx_channel + 1];
sprintf(buff, "%c:%s", vtxBandLetter, vtxChannelName); tfp_sprintf(buff, "%c:%s", vtxBandLetter, vtxChannelName);
#elif defined(USE_RTC6705) #elif defined(USE_RTC6705)
sprintf(buff, "CH:%d", current_vtx_channel % CHANNELS_PER_BAND + 1); tfp_sprintf(buff, "CH:%d", current_vtx_channel % CHANNELS_PER_BAND + 1);
#endif #endif
break; break;
} }
@ -409,27 +410,27 @@ static void osdDrawSingleElement(uint8_t item)
case OSD_ROLL_PIDS: case OSD_ROLL_PIDS:
{ {
const pidProfile_t *pidProfile = currentPidProfile; const pidProfile_t *pidProfile = currentPidProfile;
sprintf(buff, "ROL %3d %3d %3d", pidProfile->P8[PIDROLL], pidProfile->I8[PIDROLL], pidProfile->D8[PIDROLL]); tfp_sprintf(buff, "ROL %3d %3d %3d", pidProfile->P8[PIDROLL], pidProfile->I8[PIDROLL], pidProfile->D8[PIDROLL]);
break; break;
} }
case OSD_PITCH_PIDS: case OSD_PITCH_PIDS:
{ {
const pidProfile_t *pidProfile = currentPidProfile; const pidProfile_t *pidProfile = currentPidProfile;
sprintf(buff, "PIT %3d %3d %3d", pidProfile->P8[PIDPITCH], pidProfile->I8[PIDPITCH], pidProfile->D8[PIDPITCH]); tfp_sprintf(buff, "PIT %3d %3d %3d", pidProfile->P8[PIDPITCH], pidProfile->I8[PIDPITCH], pidProfile->D8[PIDPITCH]);
break; break;
} }
case OSD_YAW_PIDS: case OSD_YAW_PIDS:
{ {
const pidProfile_t *pidProfile = currentPidProfile; const pidProfile_t *pidProfile = currentPidProfile;
sprintf(buff, "YAW %3d %3d %3d", pidProfile->P8[PIDYAW], pidProfile->I8[PIDYAW], pidProfile->D8[PIDYAW]); tfp_sprintf(buff, "YAW %3d %3d %3d", pidProfile->P8[PIDYAW], pidProfile->I8[PIDYAW], pidProfile->D8[PIDYAW]);
break; break;
} }
case OSD_POWER: case OSD_POWER:
{ {
sprintf(buff, "%dW", getAmperage() * getBatteryVoltage() / 1000); tfp_sprintf(buff, "%dW", getAmperage() * getBatteryVoltage() / 1000);
break; break;
} }
@ -437,7 +438,7 @@ static void osdDrawSingleElement(uint8_t item)
{ {
const uint8_t pidProfileIndex = getCurrentPidProfileIndex(); const uint8_t pidProfileIndex = getCurrentPidProfileIndex();
const uint8_t rateProfileIndex = getCurrentControlRateProfileIndex(); const uint8_t rateProfileIndex = getCurrentControlRateProfileIndex();
sprintf(buff, "%d-%d", pidProfileIndex + 1, rateProfileIndex + 1); tfp_sprintf(buff, "%d-%d", pidProfileIndex + 1, rateProfileIndex + 1);
break; break;
} }
@ -445,11 +446,11 @@ static void osdDrawSingleElement(uint8_t item)
{ {
switch(getBatteryState()) { switch(getBatteryState()) {
case BATTERY_WARNING: case BATTERY_WARNING:
sprintf(buff, "LOW BATTERY"); tfp_sprintf(buff, "LOW BATTERY");
break; break;
case BATTERY_CRITICAL: case BATTERY_CRITICAL:
sprintf(buff, "LAND NOW"); tfp_sprintf(buff, "LAND NOW");
elemOffsetX += 1; elemOffsetX += 1;
break; break;
@ -463,7 +464,7 @@ static void osdDrawSingleElement(uint8_t item)
{ {
uint16_t cellV = getBatteryVoltage() * 10 / getBatteryCellCount(); uint16_t cellV = getBatteryVoltage() * 10 / getBatteryCellCount();
buff[0] = SYM_BATT_5; buff[0] = SYM_BATT_5;
sprintf(buff + 1, "%d.%dV", cellV / 100, cellV % 100); tfp_sprintf(buff + 1, "%d.%dV", cellV / 100, cellV % 100);
break; break;
} }
@ -602,7 +603,7 @@ void osdInit(displayPort_t *osdDisplayPortToUse)
osdDrawLogo(3, 1); osdDrawLogo(3, 1);
char string_buffer[30]; char string_buffer[30];
sprintf(string_buffer, "V%s", FC_VERSION_STRING); tfp_sprintf(string_buffer, "V%s", FC_VERSION_STRING);
displayWrite(osdDisplayPort, 20, 6, string_buffer); displayWrite(osdDisplayPort, 20, 6, string_buffer);
#ifdef CMS #ifdef CMS
displayWrite(osdDisplayPort, 7, 8, CMS_STARTUP_HELP_TEXT1); displayWrite(osdDisplayPort, 7, 8, CMS_STARTUP_HELP_TEXT1);
@ -762,7 +763,7 @@ static void osdShowStats(void)
} }
displayWrite(osdDisplayPort, 2, top, "MIN BATTERY :"); displayWrite(osdDisplayPort, 2, top, "MIN BATTERY :");
sprintf(buff, "%d.%1dV", stats.min_voltage / 10, stats.min_voltage % 10); tfp_sprintf(buff, "%d.%1dV", stats.min_voltage / 10, stats.min_voltage % 10);
displayWrite(osdDisplayPort, 22, top++, buff); displayWrite(osdDisplayPort, 22, top++, buff);
displayWrite(osdDisplayPort, 2, top, "MIN RSSI :"); displayWrite(osdDisplayPort, 2, top, "MIN RSSI :");
@ -784,7 +785,7 @@ static void osdShowStats(void)
displayWrite(osdDisplayPort, 2, top, "MAX ALTITUDE :"); displayWrite(osdDisplayPort, 2, top, "MAX ALTITUDE :");
int32_t alt = osdGetAltitude(stats.max_altitude); int32_t alt = osdGetAltitude(stats.max_altitude);
sprintf(buff, "%c%d.%01d%c", alt < 0 ? '-' : ' ', abs(alt / 100), abs((alt % 100) / 10), osdGetAltitudeSymbol()); tfp_sprintf(buff, "%c%d.%01d%c", alt < 0 ? '-' : ' ', abs(alt / 100), abs((alt % 100) / 10), osdGetAltitudeSymbol());
displayWrite(osdDisplayPort, 22, top++, buff); displayWrite(osdDisplayPort, 22, top++, buff);
#ifdef BLACKBOX #ifdef BLACKBOX

View file

@ -98,7 +98,7 @@ void osdSlaveInit(displayPort_t *osdDisplayPortToUse)
osdDrawLogo(3, 1); osdDrawLogo(3, 1);
char string_buffer[30]; char string_buffer[30];
sprintf(string_buffer, "V%s", FC_VERSION_STRING); tfp_sprintf(string_buffer, "V%s", FC_VERSION_STRING);
displayWrite(osdDisplayPort, 20, 6, string_buffer); displayWrite(osdDisplayPort, 20, 6, string_buffer);
displayWrite(osdDisplayPort, 13, 6, "OSD"); displayWrite(osdDisplayPort, 13, 6, "OSD");
@ -139,7 +139,7 @@ void osdSlaveUpdate(timeUs_t currentTimeUs)
#ifdef OSD_SLAVE_DEBUG #ifdef OSD_SLAVE_DEBUG
char buff[32]; char buff[32];
for (int i = 0; i < 4; i ++) { for (int i = 0; i < 4; i ++) {
sprintf(buff, "%5d", debug[i]); tfp_sprintf(buff, "%5d", debug[i]);
displayWrite(osdDisplayPort, i * 8, 0, buff); displayWrite(osdDisplayPort, i * 8, 0, buff);
} }
#endif #endif

View file

@ -19,8 +19,6 @@
#include <stdio.h> #include <stdio.h>
#include <stdlib.h> #include <stdlib.h>
#include <math.h> #include <math.h>
#define printf printf
#define sprintf sprintf
#include <errno.h> #include <errno.h>
#include <time.h> #include <time.h>