Skip to content

Commit

Permalink
OSD: add input throttle element for Plane and Copter (ArduPilot#31)
Browse files Browse the repository at this point in the history
  • Loading branch information
shellixyz committed Jun 15, 2022
1 parent c4131c0 commit ec3dcb5
Show file tree
Hide file tree
Showing 5 changed files with 36 additions and 3 deletions.
3 changes: 3 additions & 0 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -872,6 +872,9 @@ class Copter : public AP_Vehicle {
void set_throttle_zero_flag(int16_t throttle_control);
void radio_passthrough_to_motors();
int16_t get_throttle_mid(void);
float get_throttle_input(bool no_deadzone=false) const override {
return (no_deadzone ? channel_throttle->get_control_in_zero_dz() : channel_throttle->get_control_in()) / 10.0f;
}

// sensors.cpp
void read_barometer(void);
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -1124,7 +1124,7 @@ class Plane : public AP_Vehicle {
bool have_reverse_throttle_rc_option;
bool allow_reverse_thrust(void) const;
bool have_reverse_thrust(void) const;
float get_throttle_input(bool no_deadzone=false) const;
float get_throttle_input(bool no_deadzone=false) const override;
float get_adjusted_throttle_input(bool no_deadzone=false) const;

#if AP_SCRIPTING_ENABLED
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_OSD/AP_OSD.h
Original file line number Diff line number Diff line change
Expand Up @@ -207,6 +207,7 @@ class AP_OSD_Screen : public AP_OSD_AbstractScreen
AP_OSD_Setting sidebars{false, 4, 5};
AP_OSD_Setting power{true, 1, 1};
AP_OSD_Setting energy{false, 0, 0};
AP_OSD_Setting rc_throttle{false, 0, 0};

// MSP OSD only
AP_OSD_Setting crosshair{false, 0, 0};
Expand Down Expand Up @@ -235,6 +236,7 @@ class AP_OSD_Screen : public AP_OSD_AbstractScreen
void draw_horizon(uint8_t x, uint8_t y);
void draw_home(uint8_t x, uint8_t y);
void draw_throttle(uint8_t x, uint8_t y);
void draw_throttle_value(uint8_t x, uint8_t y, float throttle_v);
void draw_heading(uint8_t x, uint8_t y);
#ifdef HAL_OSD_SIDEBAR_ENABLE
void draw_sidebars(uint8_t x, uint8_t y);
Expand Down Expand Up @@ -286,6 +288,7 @@ class AP_OSD_Screen : public AP_OSD_AbstractScreen
void draw_hgt_abvterr(uint8_t x, uint8_t y);
void draw_fence(uint8_t x, uint8_t y);
void draw_rngf(uint8_t x, uint8_t y);
void draw_rc_throttle(uint8_t x, uint8_t y);


struct {
Expand Down
29 changes: 27 additions & 2 deletions libraries/AP_OSD/AP_OSD_Screen.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1088,6 +1088,22 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info2[] = {
// @Range: 0 15
AP_SUBGROUPINFO(energy, "ENERGY", 63, AP_OSD_Screen, AP_OSD_Setting),

// @Param: RC_THR_EN
// @DisplayName: RC_THR_EN
// @Description: Displays input throttle value (plane only)
// @Values: 0:Disabled,1:Enabled

// @Param: RC_THR_X
// @DisplayName: RC_THR_X
// @Description: Horizontal position on screen
// @Range: 0 29

// @Param: RC_THR_Y
// @DisplayName: RC_THR_Y
// @Description: Vertical position on screen
// @Range: 0 15
AP_SUBGROUPINFO(rc_throttle, "RC_THR", 62, AP_OSD_Screen, AP_OSD_Setting),

AP_GROUPEND
};

Expand Down Expand Up @@ -1683,11 +1699,10 @@ void AP_OSD_Screen::draw_heading(uint8_t x, uint8_t y)
backend->write(x, y, false, "%3d%c", yaw, SYMBOL(SYM_DEGR));
}

void AP_OSD_Screen::draw_throttle(uint8_t x, uint8_t y)
void AP_OSD_Screen::draw_throttle_value(uint8_t x, uint8_t y, float throttle_v)
{
const char *format;
uint8_t spaces;
float throttle_v = gcs().get_hud_throttle();
float throttle_abs = fabsf(throttle_v);
if (osd->options & AP_OSD::OPTION_ONE_DECIMAL_THROTTLE) {
if (throttle_abs < 9.95) {
Expand Down Expand Up @@ -1718,6 +1733,11 @@ void AP_OSD_Screen::draw_throttle(uint8_t x, uint8_t y)
backend->write(x + spaces, y, false, format, throttle_v, SYMBOL(SYM_PCNT));
}

void AP_OSD_Screen::draw_throttle(uint8_t x, uint8_t y)
{
draw_throttle_value(x, y, gcs().get_hud_throttle());
}

#if HAL_OSD_SIDEBAR_ENABLE

void AP_OSD_Screen::draw_sidebars(uint8_t x, uint8_t y)
Expand Down Expand Up @@ -2338,6 +2358,10 @@ void AP_OSD_Screen::draw_rngf(uint8_t x, uint8_t y)
}
}

void AP_OSD_Screen::draw_rc_throttle(uint8_t x, uint8_t y) {
draw_throttle_value(x, y, AP::vehicle()->get_throttle_input(true));
}

#define DRAW_SETTING(n) if (n.enabled) draw_ ## n(n.xpos, n.ypos)

#if HAL_WITH_OSD_BITMAP || HAL_WITH_MSP_DISPLAYPORT
Expand Down Expand Up @@ -2420,6 +2444,7 @@ void AP_OSD_Screen::draw(void)
DRAW_SETTING(eff);
DRAW_SETTING(callsign);
DRAW_SETTING(current2);
DRAW_SETTING(rc_throttle);
}
#endif
#endif // OSD_ENABLED
2 changes: 2 additions & 0 deletions libraries/AP_Vehicle/AP_Vehicle.h
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,8 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks {
// parameters for example.
void notify_no_such_mode(uint8_t mode_number);

virtual float get_throttle_input(bool no_deadzone=false) const { return 0; }

/*
common parameters for fixed wing aircraft
*/
Expand Down

0 comments on commit ec3dcb5

Please sign in to comment.