mirror of https://github.com/ArduPilot/ardupilot
Add reversing for PWM outputs in angle_to_pwm case.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1566 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
bf3b5c2f7c
commit
3443a7817d
|
@ -40,6 +40,13 @@ RC_Channel::set_reverse(bool reverse)
|
|||
else _reverse = 1;
|
||||
}
|
||||
|
||||
bool
|
||||
RC_Channel::get_reverse(void)
|
||||
{
|
||||
if (_reverse==-1) return 1;
|
||||
else return 0;
|
||||
}
|
||||
|
||||
void
|
||||
RC_Channel::set_filter(bool filter)
|
||||
{
|
||||
|
@ -178,11 +185,19 @@ RC_Channel::pwm_to_angle()
|
|||
|
||||
int16_t
|
||||
RC_Channel::angle_to_pwm()
|
||||
{
|
||||
if(_reverse == -1)
|
||||
{
|
||||
if(servo_out < 0)
|
||||
return ( -1 * ((long)servo_out * (long)(radio_max - radio_trim)) / (long)_high);
|
||||
else
|
||||
return ( -1 * ((long)servo_out * (long)(radio_trim - radio_min)) / (long)_high);
|
||||
} else {
|
||||
if(servo_out > 0)
|
||||
return ((long)servo_out * (long)(radio_max - radio_trim)) / (long)_high;
|
||||
else
|
||||
return ((long)servo_out * (long)(radio_trim - radio_min)) / (long)_high;
|
||||
}
|
||||
|
||||
//return (((float)servo_out / (float)_high) * (float)(radio_max - radio_trim));
|
||||
//return (((float)servo_out / (float)_high) * (float)(radio_trim - radio_min));
|
||||
|
|
|
@ -52,6 +52,7 @@ class RC_Channel{
|
|||
void set_range(int low, int high);
|
||||
void set_angle(int angle);
|
||||
void set_reverse(bool reverse);
|
||||
bool get_reverse(void);
|
||||
|
||||
// read input from APM_RC - create a control_in value
|
||||
void set_pwm(int pwm);
|
||||
|
|
Loading…
Reference in New Issue