AntennaTracker: add push command for AntennaTracker servos

This commit is contained in:
Ep Pravitra 2024-11-24 22:36:20 +07:00
parent 85f8ae8aa3
commit d67ba9b3aa
4 changed files with 11 additions and 1 deletions

View File

@ -30,8 +30,10 @@ bool ModeServoTest::set_servo(uint8_t servo_num, uint16_t pwm)
SRV_Channels::constrain_pwm(SRV_Channel::k_tracker_pitch);
}
auto &srv = AP::srv();
SRV_Channels::calc_pwm();
SRV_Channels::output_ch_all();
srv.push();
// return success
return true;

View File

@ -7,8 +7,10 @@
// init_servos - initialises the servos
void Tracker::init_servos()
{
auto &srv = AP::srv();
// update assigned functions and enable auxiliary servos
AP::srv().enable_aux_servos();
srv.enable_aux_servos();
SRV_Channels::set_default_function(CH_YAW, SRV_Channel::k_tracker_yaw);
SRV_Channels::set_default_function(CH_PITCH, SRV_Channel::k_tracker_pitch);
@ -21,6 +23,7 @@ void Tracker::init_servos()
SRV_Channels::calc_pwm();
SRV_Channels::output_ch_all();
srv.push();
yaw_servo_out_filt.set_cutoff_frequency(SERVO_OUT_FILT_HZ);
pitch_servo_out_filt.set_cutoff_frequency(SERVO_OUT_FILT_HZ);

View File

@ -161,11 +161,14 @@ void Tracker::disarm_servos()
*/
void Tracker::prepare_servos()
{
auto &srv = AP::srv();
start_time_ms = AP_HAL::millis();
SRV_Channels::set_output_limit(SRV_Channel::k_tracker_yaw, SRV_Channel::Limit::TRIM);
SRV_Channels::set_output_limit(SRV_Channel::k_tracker_pitch, SRV_Channel::Limit::TRIM);
SRV_Channels::calc_pwm();
SRV_Channels::output_ch_all();
srv.push();
}
void Tracker::set_mode(Mode &newmode, const ModeReason reason)

View File

@ -121,8 +121,10 @@ void Tracker::update_tracking(void)
}
// convert servo_out to radio_out and send to servo
auto &srv = AP::srv();
SRV_Channels::calc_pwm();
SRV_Channels::output_ch_all();
srv.push();
return;
}