mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-24 00:35:34 +03:00
Update
- Added horizontal wind speed to the programming framework. - Added min ground speed and horizontal wind speed to programming framework docs. Along with a couple of missing entries - Added min ground speed to the OSD doc, plus another that was missing.
This commit is contained in:
parent
586ca6a720
commit
5b9d5a7625
4 changed files with 23 additions and 0 deletions
|
@ -196,6 +196,8 @@ Here are the OSD Elements provided by INAV.
|
||||||
| 163 | OSD_COURSE_TO_FENCE | 8.0.0 | |
|
| 163 | OSD_COURSE_TO_FENCE | 8.0.0 | |
|
||||||
| 164 | OSD_H_DIST_TO_FENCE | 8.0.0 | |
|
| 164 | OSD_H_DIST_TO_FENCE | 8.0.0 | |
|
||||||
| 165 | OSD_V_DIST_TO_FENCE | 8.0.0 | |
|
| 165 | OSD_V_DIST_TO_FENCE | 8.0.0 | |
|
||||||
|
| 166 | OSD_NAV_FW_ALT_CONTROL_RESPONSE | 8.0.0 | |
|
||||||
|
| 167 | OSD_NAV_MIN_GROUND_SPEED | 9.0.0 | |
|
||||||
|
|
||||||
# Pilot Logos
|
# Pilot Logos
|
||||||
|
|
||||||
|
|
|
@ -101,6 +101,7 @@ IPF can be edited using INAV Configurator user interface, or via CLI. To use COn
|
||||||
| 52 | LED Pin PWM | Value `Operand A` from [`0` : `100`] starts PWM generation on LED Pin. See [LED pin PWM](LED%20pin%20PWM.md). Any other value stops PWM generation (stop to allow ws2812 LEDs updates in shared modes). |
|
| 52 | LED Pin PWM | Value `Operand A` from [`0` : `100`] starts PWM generation on LED Pin. See [LED pin PWM](LED%20pin%20PWM.md). Any other value stops PWM generation (stop to allow ws2812 LEDs updates in shared modes). |
|
||||||
| 53 | Disable GPS Sensor Fix | Disables the GNSS sensor fix. For testing GNSS failure. |
|
| 53 | Disable GPS Sensor Fix | Disables the GNSS sensor fix. For testing GNSS failure. |
|
||||||
| 54 | Mag calibration | Trigger a magnetometer calibration. |
|
| 54 | Mag calibration | Trigger a magnetometer calibration. |
|
||||||
|
| 55 | Override Minimum Ground Speed | When active, sets the minimum ground speed to the value specified in `Operand A` [m/s]. Minimum allowed value is set in `nav_min_ground_speed`. Maximum value is `150` |
|
||||||
|
|
||||||
### Operands
|
### Operands
|
||||||
|
|
||||||
|
@ -163,6 +164,10 @@ IPF can be edited using INAV Configurator user interface, or via CLI. To use COn
|
||||||
| 41 | FW Land Sate | Integer `1` - `5`, indicates the status of the FW landing, 0 Idle, 1 Downwind, 2 Base Leg, 3 Final Approach, 4 Glide, 5 Flare |
|
| 41 | FW Land Sate | Integer `1` - `5`, indicates the status of the FW landing, 0 Idle, 1 Downwind, 2 Base Leg, 3 Final Approach, 4 Glide, 5 Flare |
|
||||||
| 42 | Current battery profile | The active battery profile. Integer `[1..MAX_PROFILE_COUNT]` |
|
| 42 | Current battery profile | The active battery profile. Integer `[1..MAX_PROFILE_COUNT]` |
|
||||||
| 43 | Flown Loiter Radius [m] | The actual loiter radius flown by a fixed wing during hold modes, in `meters` |
|
| 43 | Flown Loiter Radius [m] | The actual loiter radius flown by a fixed wing during hold modes, in `meters` |
|
||||||
|
| 44 | Downlink Link Quality | |
|
||||||
|
| 45 | Uplink RSSI [dBm] | |
|
||||||
|
| 46 | Minimum Ground Speed [m/s] | The current minimum ground speed allowed in navigation flight modes |
|
||||||
|
| 47 | Horizontal Wind Speed [cm/s] | Estimated wind speed. If the wind estimator is unavailble or the wind speed is invalid, -1 is returned |
|
||||||
|
|
||||||
#### FLIGHT_MODE
|
#### FLIGHT_MODE
|
||||||
|
|
||||||
|
|
|
@ -47,6 +47,7 @@
|
||||||
#include "flight/imu.h"
|
#include "flight/imu.h"
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
#include "flight/mixer_profile.h"
|
#include "flight/mixer_profile.h"
|
||||||
|
#include "flight/wind_estimator.h"
|
||||||
#include "drivers/io_port_expander.h"
|
#include "drivers/io_port_expander.h"
|
||||||
#include "io/osd_common.h"
|
#include "io/osd_common.h"
|
||||||
#include "sensors/diagnostics.h"
|
#include "sensors/diagnostics.h"
|
||||||
|
@ -734,6 +735,20 @@ static int logicConditionGetFlightOperandValue(int operand) {
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case LOGIC_CONDITION_OPERAND_FLIGHT_HORIZONTAL_WIND_SPEED: // cm/s
|
||||||
|
#ifdef USE_WIND_ESTIMATOR
|
||||||
|
{
|
||||||
|
if (isEstimatedWindSpeedValid()) {
|
||||||
|
uint16_t angle;
|
||||||
|
return getEstimatedHorizontalWindSpeed(&angle);
|
||||||
|
} else
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
return -1;
|
||||||
|
#endif
|
||||||
|
break;
|
||||||
|
|
||||||
case LOGIC_CONDITION_OPERAND_FLIGHT_ALTITUDE: // cm
|
case LOGIC_CONDITION_OPERAND_FLIGHT_ALTITUDE: // cm
|
||||||
return constrain(getEstimatedActualPosition(Z), INT32_MIN, INT32_MAX);
|
return constrain(getEstimatedActualPosition(Z), INT32_MIN, INT32_MAX);
|
||||||
break;
|
break;
|
||||||
|
|
|
@ -148,6 +148,7 @@ typedef enum {
|
||||||
LOGIC_CONDITION_OPERAND_FLIGHT_LQ_DOWNLINK, // 44
|
LOGIC_CONDITION_OPERAND_FLIGHT_LQ_DOWNLINK, // 44
|
||||||
LOGIC_CONDITION_OPERAND_FLIGHT_UPLINK_RSSI_DBM, // 45
|
LOGIC_CONDITION_OPERAND_FLIGHT_UPLINK_RSSI_DBM, // 45
|
||||||
LOGIC_CONDITION_OPERAND_FLIGHT_MIN_GROUND_SPEED, // m/s // 46
|
LOGIC_CONDITION_OPERAND_FLIGHT_MIN_GROUND_SPEED, // m/s // 46
|
||||||
|
LOGIC_CONDITION_OPERAND_FLIGHT_HORIZONTAL_WIND_SPEED, // cm/s // 47
|
||||||
} logicFlightOperands_e;
|
} logicFlightOperands_e;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue