#include "Tracker.h"12/*3* Code to move pitch and yaw servos to attain a target heading or pitch4*/56// init_servos - initialises the servos7void Tracker::init_servos()8{9// update assigned functions and enable auxiliary servos10AP::srv().enable_aux_servos();1112SRV_Channels::set_default_function(CH_YAW, SRV_Channel::k_tracker_yaw);13SRV_Channels::set_default_function(CH_PITCH, SRV_Channel::k_tracker_pitch);1415// yaw range is +/- (YAW_RANGE parameter/2) converted to centi-degrees16SRV_Channels::set_angle(SRV_Channel::k_tracker_yaw, g.yaw_range * 100/2);1718// pitch range is +/- (PITCH_MIN/MAX parameters/2) converted to centi-degrees19SRV_Channels::set_angle(SRV_Channel::k_tracker_pitch, (-g.pitch_min+g.pitch_max) * 100/2);2021SRV_Channels::calc_pwm();22SRV_Channels::output_ch_all();2324yaw_servo_out_filt.set_cutoff_frequency(SERVO_OUT_FILT_HZ);25pitch_servo_out_filt.set_cutoff_frequency(SERVO_OUT_FILT_HZ);26}2728/**29update the pitch (elevation) servo. The aim is to drive the boards ahrs pitch to the30requested pitch, so the board (and therefore the antenna) will be pointing at the target31*/32void Tracker::update_pitch_servo(float pitch)33{34// store the target/actual values for tuning because update_error() will reset them to zero35const AP_PIDInfo *pid_info = &g.pidPitch2Srv.get_pid_info();36const float target = pid_info->target, actual = pid_info->actual;3738switch ((enum ServoType)g.servo_pitch_type.get()) {39case SERVO_TYPE_ONOFF:40update_pitch_onoff_servo(pitch);41break;4243case SERVO_TYPE_CR:44update_pitch_cr_servo(pitch);45break;4647case SERVO_TYPE_POSITION:48default:49update_pitch_position_servo();50break;51}5253g.pidPitch2Srv.set_target_rate(target);54g.pidPitch2Srv.set_actual_rate(actual);55}5657/**58update the pitch (elevation) servo. The aim is to drive the boards ahrs pitch to the59requested pitch, so the board (and therefore the antenna) will be pointing at the target60*/61void Tracker::update_pitch_position_servo()62{63int32_t pitch_min_cd = g.pitch_min*100;64int32_t pitch_max_cd = g.pitch_max*100;65// Need to configure your servo so that increasing servo_out causes increase in pitch/elevation (ie pointing higher into the sky,66// above the horizon. On my antenna tracker this requires the pitch/elevation servo to be reversed67// param set RC2_REV -168//69// The pitch servo (RC channel 2) is configured for servo_out of -9000-0-9000 servo_out,70// which will drive the servo from RC2_MIN to RC2_MAX usec pulse width.71// Therefore, you must set RC2_MIN and RC2_MAX so that your servo drives the antenna altitude between -90 to 90 exactly72// To drive my HS-645MG servos through their full 180 degrees of rotational range, I have to set:73// param set RC2_MAX 254074// param set RC2_MIN 64075//76// You will also need to tune the pitch PID to suit your antenna and servos. I use:77// PITCH2SRV_P 0.10000078// PITCH2SRV_I 0.02000079// PITCH2SRV_D 0.00000080// PITCH2SRV_IMAX 4000.0000008182// calculate new servo position83float new_servo_out = SRV_Channels::get_output_scaled(SRV_Channel::k_tracker_pitch) + g.pidPitch2Srv.update_error(nav_status.angle_error_pitch, G_Dt);8485// position limit pitch servo86if (new_servo_out <= pitch_min_cd) {87new_servo_out = pitch_min_cd;88g.pidPitch2Srv.reset_I();89}90if (new_servo_out >= pitch_max_cd) {91new_servo_out = pitch_max_cd;92g.pidPitch2Srv.reset_I();93}94// rate limit pitch servo95SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_pitch, new_servo_out);9697if (pitch_servo_out_filt_init) {98pitch_servo_out_filt.apply(new_servo_out, G_Dt);99} else {100pitch_servo_out_filt.reset(new_servo_out);101pitch_servo_out_filt_init = true;102}103}104105106/**107update the pitch (elevation) servo. The aim is to drive the boards ahrs pitch to the108requested pitch, so the board (and therefore the antenna) will be pointing at the target109*/110void Tracker::update_pitch_onoff_servo(float pitch) const111{112int32_t pitch_min_cd = g.pitch_min*100;113int32_t pitch_max_cd = g.pitch_max*100;114115float acceptable_error = g.onoff_pitch_rate * g.onoff_pitch_mintime;116if (fabsf(nav_status.angle_error_pitch) < acceptable_error) {117SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_pitch, 0);118} else if ((nav_status.angle_error_pitch > 0) && (pitch*100>pitch_min_cd)) {119// positive error means we are pointing too low, so push the120// servo up121SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_pitch, -9000);122} else if (pitch*100<pitch_max_cd) {123// negative error means we are pointing too high, so push the124// servo down125SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_pitch, 9000);126}127}128129/**130update the pitch for continuous rotation servo131*/132void Tracker::update_pitch_cr_servo(float pitch)133{134const float pitch_out = constrain_float(g.pidPitch2Srv.update_error(nav_status.angle_error_pitch, G_Dt), -(-g.pitch_min+g.pitch_max) * 100/2, (-g.pitch_min+g.pitch_max) * 100/2);135SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_pitch, pitch_out);136}137138/**139update the yaw (azimuth) servo.140*/141void Tracker::update_yaw_servo(float yaw)142{143// store the target/actual values for tuning because update_error() will reset them to zero144const AP_PIDInfo *pid_info = &g.pidYaw2Srv.get_pid_info();145const float target = pid_info->target, actual = pid_info->actual;146147switch ((enum ServoType)g.servo_yaw_type.get()) {148case SERVO_TYPE_ONOFF:149update_yaw_onoff_servo(yaw);150break;151152case SERVO_TYPE_CR:153update_yaw_cr_servo(yaw);154break;155156case SERVO_TYPE_POSITION:157default:158update_yaw_position_servo();159break;160}161162g.pidYaw2Srv.set_target_rate(target);163g.pidYaw2Srv.set_actual_rate(actual);164}165166/**167update the yaw (azimuth) servo. The aim is to drive the boards ahrs168yaw to the requested yaw, so the board (and therefore the antenna)169will be pointing at the target170*/171void Tracker::update_yaw_position_servo()172{173int32_t yaw_limit_cd = g.yaw_range*100/2;174175// Antenna as Ballerina. Use with antenna that do not have continuously rotating servos, ie at some point in rotation176// the servo limits are reached and the servo has to slew 360 degrees to the 'other side' to keep tracking.177//178// This algorithm accounts for the fact that the antenna mount may not be aligned with North179// (in fact, any alignment is permissible), and that the alignment may change (possibly rapidly) over time180// (as when the antenna is mounted on a moving, turning vehicle)181//182// With my antenna mount, large pwm output drives the antenna anticlockwise, so need:183// param set RC1_REV -1184// to reverse the servo. Yours may be different185//186// You MUST set RC1_MIN and RC1_MAX so that your servo drives the antenna azimuth from -180 to 180 relative187// to the mount.188// To drive my HS-645MG servos through their full 180 degrees of rotational range and therefore the189// antenna through a full 360 degrees, I have to set:190// param set RC1_MAX 2380191// param set RC1_MIN 680192// According to the specs at https://www.servocity.com/html/hs-645mg_ultra_torque.html,193// that should be 600 through 2400, but the azimuth gearing in my antenna pointer is not exactly 2:1194195/*196a positive error means that we need to rotate clockwise197a negative error means that we need to rotate counter-clockwise198199Use our current yawspeed to determine if we are moving in the200right direction201*/202203float servo_change = g.pidYaw2Srv.update_error(nav_status.angle_error_yaw, G_Dt);204servo_change = constrain_float(servo_change, -18000, 18000);205float new_servo_out = constrain_float(SRV_Channels::get_output_scaled(SRV_Channel::k_tracker_yaw) + servo_change, -18000, 18000);206207// position limit yaw servo208if (new_servo_out <= -yaw_limit_cd) {209new_servo_out = -yaw_limit_cd;210g.pidYaw2Srv.reset_I();211}212if (new_servo_out >= yaw_limit_cd) {213new_servo_out = yaw_limit_cd;214g.pidYaw2Srv.reset_I();215}216217SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_yaw, new_servo_out);218219if (yaw_servo_out_filt_init) {220yaw_servo_out_filt.apply(new_servo_out, G_Dt);221} else {222yaw_servo_out_filt.reset(new_servo_out);223yaw_servo_out_filt_init = true;224}225}226227228/**229update the yaw (azimuth) servo. The aim is to drive the boards ahrs230yaw to the requested yaw, so the board (and therefore the antenna)231will be pointing at the target232*/233void Tracker::update_yaw_onoff_servo(float yaw) const234{235float acceptable_error = g.onoff_yaw_rate * g.onoff_yaw_mintime;236if (fabsf(nav_status.angle_error_yaw * 0.01f) < acceptable_error) {237SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_yaw, 0);238} else if (nav_status.angle_error_yaw * 0.01f > 0) {239// positive error means we are counter-clockwise of the target, so240// move clockwise241SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_yaw, 18000);242} else {243// negative error means we are clockwise of the target, so244// move counter-clockwise245SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_yaw, -18000);246}247}248249/**250update the yaw continuous rotation servo251*/252void Tracker::update_yaw_cr_servo(float yaw)253{254const float yaw_out = constrain_float(-g.pidYaw2Srv.update_error(nav_status.angle_error_yaw, G_Dt), -g.yaw_range * 100/2, g.yaw_range * 100/2);255SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_yaw, yaw_out);256}257258259