Copter: use convenience manual_override method
This commit is contained in:
parent
32b29b3394
commit
86bd531b24
@ -879,15 +879,10 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
||||
|
||||
uint32_t tnow = AP_HAL::millis();
|
||||
|
||||
int16_t roll = (packet.y == INT16_MAX) ? 0 : copter.channel_roll->get_radio_min() + (copter.channel_roll->get_radio_max() - copter.channel_roll->get_radio_min()) * (packet.y + 1000) / 2000.0f;
|
||||
int16_t pitch = (packet.x == INT16_MAX) ? 0 : copter.channel_pitch->get_radio_min() + (copter.channel_pitch->get_radio_max() - copter.channel_pitch->get_radio_min()) * (-packet.x + 1000) / 2000.0f;
|
||||
int16_t throttle = (packet.z == INT16_MAX) ? 0 : copter.channel_throttle->get_radio_min() + (copter.channel_throttle->get_radio_max() - copter.channel_throttle->get_radio_min()) * (packet.z) / 1000.0f;
|
||||
int16_t yaw = (packet.r == INT16_MAX) ? 0 : copter.channel_yaw->get_radio_min() + (copter.channel_yaw->get_radio_max() - copter.channel_yaw->get_radio_min()) * (packet.r + 1000) / 2000.0f;
|
||||
|
||||
RC_Channels::set_override(uint8_t(copter.rcmap.roll() - 1), roll, tnow);
|
||||
RC_Channels::set_override(uint8_t(copter.rcmap.pitch() - 1), pitch, tnow);
|
||||
RC_Channels::set_override(uint8_t(copter.rcmap.throttle() - 1), throttle, tnow);
|
||||
RC_Channels::set_override(uint8_t(copter.rcmap.yaw() - 1), yaw, tnow);
|
||||
manual_override(copter.channel_roll, packet.y, 1000, 2000, tnow);
|
||||
manual_override(copter.channel_pitch, packet.x, 1000, 2000, tnow, true);
|
||||
manual_override(copter.channel_throttle, packet.z, 0, 1000, tnow);
|
||||
manual_override(copter.channel_yaw, packet.r, 1000, 2000, tnow);
|
||||
|
||||
// a manual control message is considered to be a 'heartbeat' from the ground station for failsafe purposes
|
||||
copter.failsafe.last_heartbeat_ms = tnow;
|
||||
|
Loading…
Reference in New Issue
Block a user