mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
RC_Channel: formatting fixes
This commit is contained in:
parent
77d5165c01
commit
cd38940ecf
@ -106,35 +106,30 @@ RC_Channel::RC_Channel(void)
|
|||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void RC_Channel::set_range(uint16_t high)
|
||||||
RC_Channel::set_range(uint16_t high)
|
|
||||||
{
|
{
|
||||||
type_in = RC_CHANNEL_TYPE_RANGE;
|
type_in = RC_CHANNEL_TYPE_RANGE;
|
||||||
high_in = high;
|
high_in = high;
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void RC_Channel::set_angle(uint16_t angle)
|
||||||
RC_Channel::set_angle(uint16_t angle)
|
|
||||||
{
|
{
|
||||||
type_in = RC_CHANNEL_TYPE_ANGLE;
|
type_in = RC_CHANNEL_TYPE_ANGLE;
|
||||||
high_in = angle;
|
high_in = angle;
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void RC_Channel::set_default_dead_zone(int16_t dzone)
|
||||||
RC_Channel::set_default_dead_zone(int16_t dzone)
|
|
||||||
{
|
{
|
||||||
dead_zone.set_default(abs(dzone));
|
dead_zone.set_default(abs(dzone));
|
||||||
}
|
}
|
||||||
|
|
||||||
bool
|
bool RC_Channel::get_reverse(void) const
|
||||||
RC_Channel::get_reverse(void) const
|
|
||||||
{
|
{
|
||||||
return bool(reversed.get());
|
return bool(reversed.get());
|
||||||
}
|
}
|
||||||
|
|
||||||
// read input from hal.rcin or overrides
|
// read input from hal.rcin or overrides
|
||||||
bool
|
bool RC_Channel::update(void)
|
||||||
RC_Channel::update(void)
|
|
||||||
{
|
{
|
||||||
if (has_override() && !rc().ignore_overrides()) {
|
if (has_override() && !rc().ignore_overrides()) {
|
||||||
radio_in = override_value;
|
radio_in = override_value;
|
||||||
@ -157,8 +152,7 @@ RC_Channel::update(void)
|
|||||||
// recompute control values with no deadzone
|
// recompute control values with no deadzone
|
||||||
// When done this way the control_in value can be used as servo_out
|
// When done this way the control_in value can be used as servo_out
|
||||||
// to give the same output as input
|
// to give the same output as input
|
||||||
void
|
void RC_Channel::recompute_pwm_no_deadzone()
|
||||||
RC_Channel::recompute_pwm_no_deadzone()
|
|
||||||
{
|
{
|
||||||
if (type_in == RC_CHANNEL_TYPE_RANGE) {
|
if (type_in == RC_CHANNEL_TYPE_RANGE) {
|
||||||
control_in = pwm_to_range_dz(0);
|
control_in = pwm_to_range_dz(0);
|
||||||
@ -193,8 +187,7 @@ int16_t RC_Channel::get_control_mid() const
|
|||||||
return an "angle in centidegrees" (normally -4500 to 4500) from
|
return an "angle in centidegrees" (normally -4500 to 4500) from
|
||||||
the current radio_in value using the specified dead_zone
|
the current radio_in value using the specified dead_zone
|
||||||
*/
|
*/
|
||||||
int16_t
|
int16_t RC_Channel::pwm_to_angle_dz_trim(uint16_t _dead_zone, uint16_t _trim) const
|
||||||
RC_Channel::pwm_to_angle_dz_trim(uint16_t _dead_zone, uint16_t _trim) const
|
|
||||||
{
|
{
|
||||||
int16_t radio_trim_high = _trim + _dead_zone;
|
int16_t radio_trim_high = _trim + _dead_zone;
|
||||||
int16_t radio_trim_low = _trim - _dead_zone;
|
int16_t radio_trim_low = _trim - _dead_zone;
|
||||||
@ -213,8 +206,7 @@ RC_Channel::pwm_to_angle_dz_trim(uint16_t _dead_zone, uint16_t _trim) const
|
|||||||
return an "angle in centidegrees" (normally -4500 to 4500) from
|
return an "angle in centidegrees" (normally -4500 to 4500) from
|
||||||
the current radio_in value using the specified dead_zone
|
the current radio_in value using the specified dead_zone
|
||||||
*/
|
*/
|
||||||
int16_t
|
int16_t RC_Channel::pwm_to_angle_dz(uint16_t _dead_zone) const
|
||||||
RC_Channel::pwm_to_angle_dz(uint16_t _dead_zone) const
|
|
||||||
{
|
{
|
||||||
return pwm_to_angle_dz_trim(_dead_zone, radio_trim);
|
return pwm_to_angle_dz_trim(_dead_zone, radio_trim);
|
||||||
}
|
}
|
||||||
@ -223,8 +215,7 @@ RC_Channel::pwm_to_angle_dz(uint16_t _dead_zone) const
|
|||||||
return an "angle in centidegrees" (normally -4500 to 4500) from
|
return an "angle in centidegrees" (normally -4500 to 4500) from
|
||||||
the current radio_in value
|
the current radio_in value
|
||||||
*/
|
*/
|
||||||
int16_t
|
int16_t RC_Channel::pwm_to_angle() const
|
||||||
RC_Channel::pwm_to_angle() const
|
|
||||||
{
|
{
|
||||||
return pwm_to_angle_dz(dead_zone);
|
return pwm_to_angle_dz(dead_zone);
|
||||||
}
|
}
|
||||||
@ -234,8 +225,7 @@ RC_Channel::pwm_to_angle() const
|
|||||||
convert a pulse width modulation value to a value in the configured
|
convert a pulse width modulation value to a value in the configured
|
||||||
range, using the specified deadzone
|
range, using the specified deadzone
|
||||||
*/
|
*/
|
||||||
int16_t
|
int16_t RC_Channel::pwm_to_range_dz(uint16_t _dead_zone) const
|
||||||
RC_Channel::pwm_to_range_dz(uint16_t _dead_zone) const
|
|
||||||
{
|
{
|
||||||
int16_t r_in = constrain_int16(radio_in, radio_min.get(), radio_max.get());
|
int16_t r_in = constrain_int16(radio_in, radio_min.get(), radio_max.get());
|
||||||
|
|
||||||
@ -255,8 +245,7 @@ RC_Channel::pwm_to_range_dz(uint16_t _dead_zone) const
|
|||||||
convert a pulse width modulation value to a value in the configured
|
convert a pulse width modulation value to a value in the configured
|
||||||
range
|
range
|
||||||
*/
|
*/
|
||||||
int16_t
|
int16_t RC_Channel::pwm_to_range() const
|
||||||
RC_Channel::pwm_to_range() const
|
|
||||||
{
|
{
|
||||||
return pwm_to_range_dz(dead_zone);
|
return pwm_to_range_dz(dead_zone);
|
||||||
}
|
}
|
||||||
@ -272,8 +261,7 @@ int16_t RC_Channel::get_control_in_zero_dz(void) const
|
|||||||
|
|
||||||
// ------------------------------------------
|
// ------------------------------------------
|
||||||
|
|
||||||
float
|
float RC_Channel::norm_input() const
|
||||||
RC_Channel::norm_input() const
|
|
||||||
{
|
{
|
||||||
float ret;
|
float ret;
|
||||||
int16_t reverse_mul = (reversed?-1:1);
|
int16_t reverse_mul = (reversed?-1:1);
|
||||||
@ -291,8 +279,7 @@ RC_Channel::norm_input() const
|
|||||||
return constrain_float(ret, -1.0f, 1.0f);
|
return constrain_float(ret, -1.0f, 1.0f);
|
||||||
}
|
}
|
||||||
|
|
||||||
float
|
float RC_Channel::norm_input_dz() const
|
||||||
RC_Channel::norm_input_dz() const
|
|
||||||
{
|
{
|
||||||
int16_t dz_min = radio_trim - dead_zone;
|
int16_t dz_min = radio_trim - dead_zone;
|
||||||
int16_t dz_max = radio_trim + dead_zone;
|
int16_t dz_max = radio_trim + dead_zone;
|
||||||
@ -323,8 +310,7 @@ float RC_Channel::norm_input_ignore_trim() const
|
|||||||
/*
|
/*
|
||||||
get percentage input from 0 to 100. This ignores the trim value.
|
get percentage input from 0 to 100. This ignores the trim value.
|
||||||
*/
|
*/
|
||||||
uint8_t
|
uint8_t RC_Channel::percent_input() const
|
||||||
RC_Channel::percent_input() const
|
|
||||||
{
|
{
|
||||||
if (radio_in <= radio_min) {
|
if (radio_in <= radio_min) {
|
||||||
return reversed?100:0;
|
return reversed?100:0;
|
||||||
|
@ -40,16 +40,12 @@ public:
|
|||||||
// for hover throttle
|
// for hover throttle
|
||||||
int16_t pwm_to_angle_dz_trim(uint16_t dead_zone, uint16_t trim) const;
|
int16_t pwm_to_angle_dz_trim(uint16_t dead_zone, uint16_t trim) const;
|
||||||
|
|
||||||
/*
|
// return a normalised input for a channel, in range -1 to 1,
|
||||||
return a normalised input for a channel, in range -1 to 1,
|
// centered around the channel trim. Ignore deadzone.
|
||||||
centered around the channel trim. Ignore deadzone.
|
|
||||||
*/
|
|
||||||
float norm_input() const;
|
float norm_input() const;
|
||||||
|
|
||||||
/*
|
// return a normalised input for a channel, in range -1 to 1,
|
||||||
return a normalised input for a channel, in range -1 to 1,
|
// centered around the channel trim. Take into account the deadzone
|
||||||
centered around the channel trim. Take into account the deadzone
|
|
||||||
*/
|
|
||||||
float norm_input_dz() const;
|
float norm_input_dz() const;
|
||||||
|
|
||||||
// return a normalised input for a channel, in range -1 to 1,
|
// return a normalised input for a channel, in range -1 to 1,
|
||||||
@ -99,7 +95,7 @@ public:
|
|||||||
|
|
||||||
AP_Int16 option; // e.g. activate EPM gripper / enable fence
|
AP_Int16 option; // e.g. activate EPM gripper / enable fence
|
||||||
|
|
||||||
// auxillary switch support:
|
// auxiliary switch support
|
||||||
void init_aux();
|
void init_aux();
|
||||||
bool read_aux();
|
bool read_aux();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user