AP_Motors: fixed setup of ESC update speeds

This commit is contained in:
Andrew Tridgell 2013-01-10 15:52:46 +11:00
parent 21e979910f
commit 03b26c7d6d
3 changed files with 14 additions and 8 deletions

View File

@ -198,10 +198,12 @@ void AP_MotorsHeli::set_update_rate( uint16_t speed_hz )
_speed_hz = speed_hz;
// setup fast channels
hal.rcout->set_freq(_motor_to_channel_map[AP_MOTORS_MOT_1], _speed_hz);
hal.rcout->set_freq(_motor_to_channel_map[AP_MOTORS_MOT_2], _speed_hz);
hal.rcout->set_freq(_motor_to_channel_map[AP_MOTORS_MOT_3], _speed_hz);
hal.rcout->set_freq(_motor_to_channel_map[AP_MOTORS_MOT_4], _speed_hz);
uint32_t mask =
1U << _motor_to_channel_map[AP_MOTORS_MOT_1] |
1U << _motor_to_channel_map[AP_MOTORS_MOT_2] |
1U << _motor_to_channel_map[AP_MOTORS_MOT_3] |
1U << _motor_to_channel_map[AP_MOTORS_MOT_4];
hal.rcout->set_freq(mask, _speed_hz);
}
// enable - starts allowing signals to be sent to motors

View File

@ -34,11 +34,13 @@ void AP_MotorsMatrix::set_update_rate( uint16_t speed_hz )
_speed_hz = speed_hz;
// check each enabled motor
uint32_t mask = 0;
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
if( motor_enabled[i] ) {
hal.rcout->set_freq( _motor_to_channel_map[i], _speed_hz );
mask |= 1U << _motor_to_channel_map[i];
}
}
hal.rcout->set_freq( mask, _speed_hz );
}
// set frame orientation (normally + or X)

View File

@ -30,9 +30,11 @@ void AP_MotorsTri::set_update_rate( uint16_t speed_hz )
_speed_hz = speed_hz;
// set update rate for the 3 motors (but not the servo on channel 7)
hal.rcout->set_freq(_motor_to_channel_map[AP_MOTORS_MOT_1], _speed_hz);
hal.rcout->set_freq(_motor_to_channel_map[AP_MOTORS_MOT_2], _speed_hz);
hal.rcout->set_freq(_motor_to_channel_map[AP_MOTORS_MOT_4], _speed_hz);
uint32_t mask =
1U << _motor_to_channel_map[AP_MOTORS_MOT_1] |
1U << _motor_to_channel_map[AP_MOTORS_MOT_2] |
1U << _motor_to_channel_map[AP_MOTORS_MOT_4];
hal.rcout->set_freq(mask, _speed_hz);
}
// enable - starts allowing signals to be sent to motors