AP_OSD: add inverted roll AH and inverted wind direction
This commit is contained in:
parent
7873aff0b8
commit
eaac477131
@ -73,7 +73,7 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
|
||||
// @Param: _OPTIONS
|
||||
// @DisplayName: OSD Options
|
||||
// @Description: This sets options that change the display
|
||||
// @Bitmask: 0:UseDecimalPack
|
||||
// @Bitmask: 0:UseDecimalPack, 1:InvertedWindPointer, 2:InvertedAHRoll
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_OPTIONS", 8, AP_OSD, options, OPTION_DECIMAL_PACK),
|
||||
|
||||
@ -163,7 +163,8 @@ void AP_OSD::update_osd()
|
||||
backend->clear();
|
||||
|
||||
update_current_screen();
|
||||
|
||||
|
||||
screen[current_screen].set_osd(this);
|
||||
screen[current_screen].set_backend(backend);
|
||||
screen[current_screen].draw();
|
||||
|
||||
|
@ -39,6 +39,7 @@ public:
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
};
|
||||
|
||||
class AP_OSD;
|
||||
|
||||
/*
|
||||
class to hold one screen of settings
|
||||
@ -55,6 +56,11 @@ public:
|
||||
backend = _backend;
|
||||
};
|
||||
|
||||
void set_osd(AP_OSD *_osd)
|
||||
{
|
||||
osd = _osd;
|
||||
};
|
||||
|
||||
// User settable parameters
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
@ -64,6 +70,7 @@ public:
|
||||
|
||||
private:
|
||||
AP_OSD_Backend *backend;
|
||||
AP_OSD *osd;
|
||||
|
||||
static const uint16_t message_show_time_ms = 20000;
|
||||
static const uint8_t message_visible_width = 26;
|
||||
@ -168,6 +175,8 @@ public:
|
||||
|
||||
enum {
|
||||
OPTION_DECIMAL_PACK = 1U<<0,
|
||||
OPTION_INVERTED_WIND = 1U<<1,
|
||||
OPTION_INVERTED_AH_ROLL = 1U<<2,
|
||||
};
|
||||
|
||||
AP_Int32 options;
|
||||
|
@ -342,6 +342,11 @@ void AP_OSD_Screen::draw_horizon(uint8_t x, uint8_t y)
|
||||
AP_AHRS &ahrs = AP::ahrs();
|
||||
float roll = ahrs.roll;
|
||||
float pitch = -ahrs.pitch;
|
||||
|
||||
//inverted roll AH
|
||||
if(osd->options.get() & AP_OSD::OPTION_INVERTED_AH_ROLL) {
|
||||
roll = -roll;
|
||||
}
|
||||
|
||||
roll = constrain_float(roll, -ah_max_roll, ah_max_roll);
|
||||
pitch = constrain_float(pitch, -ah_max_pitch, ah_max_pitch);
|
||||
@ -434,6 +439,9 @@ void AP_OSD_Screen::draw_wind(uint8_t x, uint8_t y)
|
||||
{
|
||||
AP_AHRS &ahrs = AP::ahrs();
|
||||
Vector3f v = ahrs.wind_estimate();
|
||||
if(osd->options.get() & AP_OSD::OPTION_INVERTED_WIND) {
|
||||
v = -v;
|
||||
}
|
||||
backend->write(x, y, false, "%c", SYM_WSPD);
|
||||
draw_speed_vector(x + 1, y, Vector2f(v.x, v.y), ahrs.yaw_sensor);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user