GCS_MAVLink: implement a convenience manual_override method

This commit is contained in:
Peter Barker 2018-05-06 15:24:30 +10:00 committed by Tom Pittenger
parent 543bb289f4
commit 30a66d9f13
2 changed files with 19 additions and 0 deletions

View File

@ -452,6 +452,8 @@ protected:
static constexpr const float magic_force_arm_value = 2989.0f;
static constexpr const float magic_force_disarm_value = 21196.0f;
void manual_override(RC_Channel *c, int16_t value_in, uint16_t offset, float scaler, const uint32_t tnow, bool reversed = false);
private:
void log_mavlink_stats();

View File

@ -4588,6 +4588,23 @@ uint64_t GCS_MAVLINK::capabilities() const
}
void GCS_MAVLINK::manual_override(RC_Channel *c, int16_t value_in, const uint16_t offset, const float scaler, const uint32_t tnow, const bool reversed)
{
if (c == nullptr) {
return;
}
int16_t override_value = 0;
if (value_in != INT16_MAX) {
const int16_t radio_min = c->get_radio_min();
const int16_t radio_max = c->get_radio_max();
if (reversed) {
value_in *= -1;
}
override_value = radio_min + (radio_max - radio_min) * (value_in + offset) / scaler;
}
c->set_override(override_value, tnow);
}
GCS &gcs()
{
return *GCS::get_singleton();