mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
SRV_Channel: fixed build warnings
This commit is contained in:
parent
93dbcf88b8
commit
6af709e617
@ -291,9 +291,9 @@ SRV_Channels::set_failsafe_pwm(SRV_Channel::Aux_servo_function_t function, uint1
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
|
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
|
||||||
const SRV_Channel &ch = channels[i];
|
const SRV_Channel &c = channels[i];
|
||||||
if (ch.function.get() == function) {
|
if (c.function.get() == function) {
|
||||||
hal.rcout->set_failsafe_pwm(1U<<ch.ch_num, pwm);
|
hal.rcout->set_failsafe_pwm(1U<<c.ch_num, pwm);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -308,10 +308,10 @@ SRV_Channels::set_failsafe_limit(SRV_Channel::Aux_servo_function_t function, SRV
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
|
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
|
||||||
const SRV_Channel &ch = channels[i];
|
const SRV_Channel &c = channels[i];
|
||||||
if (ch.function.get() == function) {
|
if (c.function.get() == function) {
|
||||||
uint16_t pwm = ch.get_limit_pwm(limit);
|
uint16_t pwm = c.get_limit_pwm(limit);
|
||||||
hal.rcout->set_failsafe_pwm(1U<<ch.ch_num, pwm);
|
hal.rcout->set_failsafe_pwm(1U<<c.ch_num, pwm);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -326,10 +326,10 @@ SRV_Channels::set_safety_limit(SRV_Channel::Aux_servo_function_t function, SRV_C
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
|
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
|
||||||
const SRV_Channel &ch = channels[i];
|
const SRV_Channel &c = channels[i];
|
||||||
if (ch.function.get() == function) {
|
if (c.function.get() == function) {
|
||||||
uint16_t pwm = ch.get_limit_pwm(limit);
|
uint16_t pwm = c.get_limit_pwm(limit);
|
||||||
hal.rcout->set_safety_pwm(1U<<ch.ch_num, pwm);
|
hal.rcout->set_safety_pwm(1U<<c.ch_num, pwm);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -344,16 +344,16 @@ SRV_Channels::set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_C
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
|
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
|
||||||
SRV_Channel &ch = channels[i];
|
SRV_Channel &c = channels[i];
|
||||||
if (ch.function.get() == function) {
|
if (c.function.get() == function) {
|
||||||
uint16_t pwm = ch.get_limit_pwm(limit);
|
uint16_t pwm = c.get_limit_pwm(limit);
|
||||||
ch.set_output_pwm(pwm);
|
c.set_output_pwm(pwm);
|
||||||
if (ch.function.get() == SRV_Channel::k_manual) {
|
if (c.function.get() == SRV_Channel::k_manual) {
|
||||||
RC_Channel *c = rc().channel(ch.ch_num);
|
RC_Channel *cin = rc().channel(c.ch_num);
|
||||||
if (c != nullptr) {
|
if (cin != nullptr) {
|
||||||
// in order for output_ch() to work for k_manual we
|
// in order for output_ch() to work for k_manual we
|
||||||
// also have to override radio_in
|
// also have to override radio_in
|
||||||
c->set_radio_in(pwm);
|
cin->set_radio_in(pwm);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -386,11 +386,11 @@ SRV_Channels::move_servo(SRV_Channel::Aux_servo_function_t function,
|
|||||||
float v = float(value - angle_min) / float(angle_max - angle_min);
|
float v = float(value - angle_min) / float(angle_max - angle_min);
|
||||||
v = constrain_float(v, 0.0f, 1.0f);
|
v = constrain_float(v, 0.0f, 1.0f);
|
||||||
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
|
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
|
||||||
SRV_Channel &ch = channels[i];
|
SRV_Channel &c = channels[i];
|
||||||
if (ch.function.get() == function) {
|
if (c.function.get() == function) {
|
||||||
float v2 = ch.get_reversed()? (1-v) : v;
|
float v2 = c.get_reversed()? (1-v) : v;
|
||||||
uint16_t pwm = ch.servo_min + v2 * (ch.servo_max - ch.servo_min);
|
uint16_t pwm = c.servo_min + v2 * (c.servo_max - c.servo_min);
|
||||||
ch.set_output_pwm(pwm);
|
c.set_output_pwm(pwm);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -618,21 +618,21 @@ void SRV_Channels::limit_slew_rate(SRV_Channel::Aux_servo_function_t function, f
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
|
for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
|
||||||
SRV_Channel &ch = channels[i];
|
SRV_Channel &c = channels[i];
|
||||||
if (ch.function == function) {
|
if (c.function == function) {
|
||||||
ch.calc_pwm(functions[function].output_scaled);
|
c.calc_pwm(functions[function].output_scaled);
|
||||||
uint16_t last_pwm = hal.rcout->read_last_sent(ch.ch_num);
|
uint16_t last_pwm = hal.rcout->read_last_sent(c.ch_num);
|
||||||
if (last_pwm == ch.output_pwm) {
|
if (last_pwm == c.output_pwm) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
uint16_t max_change = (ch.get_output_max() - ch.get_output_min()) * slew_rate * dt * 0.01f;
|
uint16_t max_change = (c.get_output_max() - c.get_output_min()) * slew_rate * dt * 0.01f;
|
||||||
if (max_change == 0 || dt > 1) {
|
if (max_change == 0 || dt > 1) {
|
||||||
// always allow some change. If dt > 1 then assume we
|
// always allow some change. If dt > 1 then assume we
|
||||||
// are just starting out, and only allow a small
|
// are just starting out, and only allow a small
|
||||||
// change for this loop
|
// change for this loop
|
||||||
max_change = 1;
|
max_change = 1;
|
||||||
}
|
}
|
||||||
ch.output_pwm = constrain_int16(ch.output_pwm, last_pwm-max_change, last_pwm+max_change);
|
c.output_pwm = constrain_int16(c.output_pwm, last_pwm-max_change, last_pwm+max_change);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -672,9 +672,9 @@ void SRV_Channels::set_output_min_max(SRV_Channel::Aux_servo_function_t function
|
|||||||
void SRV_Channels::constrain_pwm(SRV_Channel::Aux_servo_function_t function)
|
void SRV_Channels::constrain_pwm(SRV_Channel::Aux_servo_function_t function)
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
|
for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
|
||||||
SRV_Channel &ch = channels[i];
|
SRV_Channel &c = channels[i];
|
||||||
if (ch.function == function) {
|
if (c.function == function) {
|
||||||
ch.output_pwm = constrain_int16(ch.output_pwm, ch.servo_min, ch.servo_max);
|
c.output_pwm = constrain_int16(c.output_pwm, c.servo_min, c.servo_max);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -863,9 +863,9 @@ void SRV_Channels::set_rc_frequency(SRV_Channel::Aux_servo_function_t function,
|
|||||||
{
|
{
|
||||||
uint16_t mask = 0;
|
uint16_t mask = 0;
|
||||||
for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
|
for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
|
||||||
SRV_Channel &ch = channels[i];
|
SRV_Channel &c = channels[i];
|
||||||
if (ch.function == function) {
|
if (c.function == function) {
|
||||||
mask |= (1U<<ch.ch_num);
|
mask |= (1U<<c.ch_num);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (mask != 0) {
|
if (mask != 0) {
|
||||||
|
Loading…
Reference in New Issue
Block a user