mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
RC_Channel: added output_trim() and read() functions
these make using rcmap in the plane code easier
This commit is contained in:
parent
033828aeb6
commit
c0058bbb03
@ -336,17 +336,28 @@ RC_Channel::norm_output()
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
void RC_Channel::output()
|
void RC_Channel::output() const
|
||||||
{
|
{
|
||||||
hal.rcout->write(_ch_out, radio_out);
|
hal.rcout->write(_ch_out, radio_out);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void RC_Channel::output_trim() const
|
||||||
|
{
|
||||||
|
hal.rcout->write(_ch_out, radio_trim);
|
||||||
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
RC_Channel::input()
|
RC_Channel::input()
|
||||||
{
|
{
|
||||||
radio_in = hal.rcin->read(_ch_out);
|
radio_in = hal.rcin->read(_ch_out);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
uint16_t
|
||||||
|
RC_Channel::read() const
|
||||||
|
{
|
||||||
|
return hal.rcin->read(_ch_out);
|
||||||
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
RC_Channel::enable_out()
|
RC_Channel::enable_out()
|
||||||
{
|
{
|
||||||
|
@ -95,7 +95,9 @@ public:
|
|||||||
int16_t pwm_to_range_dz(uint16_t dead_zone);
|
int16_t pwm_to_range_dz(uint16_t dead_zone);
|
||||||
int16_t range_to_pwm();
|
int16_t range_to_pwm();
|
||||||
|
|
||||||
void output();
|
void output() const;
|
||||||
|
void output_trim() const;
|
||||||
|
uint16_t read() const;
|
||||||
void input();
|
void input();
|
||||||
void enable_out();
|
void enable_out();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user