AP_HAL: RCOutput_Tap: remove feedback from ESCs

This is not currently working on Aero, the only user of it right now,
and it has been commented out. Remove dead code.
This commit is contained in:
Lucas De Marchi 2017-09-26 14:36:13 -07:00
parent d3a1ed9792
commit 2c3054cbae
2 changed files with 0 additions and 8 deletions

View File

@ -553,11 +553,6 @@ void RCOutput_Tap::push()
* REV: Reverse direction
*/
// TODO: enable feedback from 1 ESC and read data back
#if 0
out[_next_channel_reply] |= RUN_FEEDBACK_ENABLE_MASK;
#endif
EscPacket packet = {0xfe, _channels_count, ESCBUS_MSG_ID_RUN};
packet.len *= sizeof(packet.d.reqRun.value[0]);
@ -570,8 +565,6 @@ void RCOutput_Tap::push()
debug("TX ERROR: ret: %d, errno: %d", ret, errno);
}
_next_channel_reply = (_next_channel_reply + 1) % _channels_count;
hal.util->perf_end(_perf_rcout);
}

View File

@ -91,7 +91,6 @@ private:
bool _corking;
uint8_t _channels_count = MAX_MOTORS;
uint8_t _next_channel_reply;
uint16_t _period[MAX_MOTORS];
uint16_t _esc_pwm_min;