Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/AntennaTracker/servos.cpp
Views: 1798
#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{34switch ((enum ServoType)g.servo_pitch_type.get()) {35case SERVO_TYPE_ONOFF:36update_pitch_onoff_servo(pitch);37break;3839case SERVO_TYPE_CR:40update_pitch_cr_servo(pitch);41break;4243case SERVO_TYPE_POSITION:44default:45update_pitch_position_servo();46break;47}48}4950/**51update the pitch (elevation) servo. The aim is to drive the boards ahrs pitch to the52requested pitch, so the board (and therefore the antenna) will be pointing at the target53*/54void Tracker::update_pitch_position_servo()55{56int32_t pitch_min_cd = g.pitch_min*100;57int32_t pitch_max_cd = g.pitch_max*100;58// Need to configure your servo so that increasing servo_out causes increase in pitch/elevation (ie pointing higher into the sky,59// above the horizon. On my antenna tracker this requires the pitch/elevation servo to be reversed60// param set RC2_REV -161//62// The pitch servo (RC channel 2) is configured for servo_out of -9000-0-9000 servo_out,63// which will drive the servo from RC2_MIN to RC2_MAX usec pulse width.64// Therefore, you must set RC2_MIN and RC2_MAX so that your servo drives the antenna altitude between -90 to 90 exactly65// To drive my HS-645MG servos through their full 180 degrees of rotational range, I have to set:66// param set RC2_MAX 254067// param set RC2_MIN 64068//69// You will also need to tune the pitch PID to suit your antenna and servos. I use:70// PITCH2SRV_P 0.10000071// PITCH2SRV_I 0.02000072// PITCH2SRV_D 0.00000073// PITCH2SRV_IMAX 4000.0000007475// calculate new servo position76float new_servo_out = SRV_Channels::get_output_scaled(SRV_Channel::k_tracker_pitch) + g.pidPitch2Srv.update_error(nav_status.angle_error_pitch, G_Dt);7778// position limit pitch servo79if (new_servo_out <= pitch_min_cd) {80new_servo_out = pitch_min_cd;81g.pidPitch2Srv.reset_I();82}83if (new_servo_out >= pitch_max_cd) {84new_servo_out = pitch_max_cd;85g.pidPitch2Srv.reset_I();86}87// rate limit pitch servo88SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_pitch, new_servo_out);8990if (pitch_servo_out_filt_init) {91pitch_servo_out_filt.apply(new_servo_out, G_Dt);92} else {93pitch_servo_out_filt.reset(new_servo_out);94pitch_servo_out_filt_init = true;95}96}979899/**100update the pitch (elevation) servo. The aim is to drive the boards ahrs pitch to the101requested pitch, so the board (and therefore the antenna) will be pointing at the target102*/103void Tracker::update_pitch_onoff_servo(float pitch) const104{105int32_t pitch_min_cd = g.pitch_min*100;106int32_t pitch_max_cd = g.pitch_max*100;107108float acceptable_error = g.onoff_pitch_rate * g.onoff_pitch_mintime;109if (fabsf(nav_status.angle_error_pitch) < acceptable_error) {110SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_pitch, 0);111} else if ((nav_status.angle_error_pitch > 0) && (pitch*100>pitch_min_cd)) {112// positive error means we are pointing too low, so push the113// servo up114SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_pitch, -9000);115} else if (pitch*100<pitch_max_cd) {116// negative error means we are pointing too high, so push the117// servo down118SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_pitch, 9000);119}120}121122/**123update the pitch for continuous rotation servo124*/125void Tracker::update_pitch_cr_servo(float pitch)126{127const 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);128SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_pitch, pitch_out);129}130131/**132update the yaw (azimuth) servo.133*/134void Tracker::update_yaw_servo(float yaw)135{136switch ((enum ServoType)g.servo_yaw_type.get()) {137case SERVO_TYPE_ONOFF:138update_yaw_onoff_servo(yaw);139break;140141case SERVO_TYPE_CR:142update_yaw_cr_servo(yaw);143break;144145case SERVO_TYPE_POSITION:146default:147update_yaw_position_servo();148break;149}150}151152/**153update the yaw (azimuth) servo. The aim is to drive the boards ahrs154yaw to the requested yaw, so the board (and therefore the antenna)155will be pointing at the target156*/157void Tracker::update_yaw_position_servo()158{159int32_t yaw_limit_cd = g.yaw_range*100/2;160161// Antenna as Ballerina. Use with antenna that do not have continuously rotating servos, ie at some point in rotation162// the servo limits are reached and the servo has to slew 360 degrees to the 'other side' to keep tracking.163//164// This algorithm accounts for the fact that the antenna mount may not be aligned with North165// (in fact, any alignment is permissible), and that the alignment may change (possibly rapidly) over time166// (as when the antenna is mounted on a moving, turning vehicle)167//168// With my antenna mount, large pwm output drives the antenna anticlockwise, so need:169// param set RC1_REV -1170// to reverse the servo. Yours may be different171//172// You MUST set RC1_MIN and RC1_MAX so that your servo drives the antenna azimuth from -180 to 180 relative173// to the mount.174// To drive my HS-645MG servos through their full 180 degrees of rotational range and therefore the175// antenna through a full 360 degrees, I have to set:176// param set RC1_MAX 2380177// param set RC1_MIN 680178// According to the specs at https://www.servocity.com/html/hs-645mg_ultra_torque.html,179// that should be 600 through 2400, but the azimuth gearing in my antenna pointer is not exactly 2:1180181/*182a positive error means that we need to rotate clockwise183a negative error means that we need to rotate counter-clockwise184185Use our current yawspeed to determine if we are moving in the186right direction187*/188189float servo_change = g.pidYaw2Srv.update_error(nav_status.angle_error_yaw, G_Dt);190servo_change = constrain_float(servo_change, -18000, 18000);191float new_servo_out = constrain_float(SRV_Channels::get_output_scaled(SRV_Channel::k_tracker_yaw) + servo_change, -18000, 18000);192193// position limit yaw servo194if (new_servo_out <= -yaw_limit_cd) {195new_servo_out = -yaw_limit_cd;196g.pidYaw2Srv.reset_I();197}198if (new_servo_out >= yaw_limit_cd) {199new_servo_out = yaw_limit_cd;200g.pidYaw2Srv.reset_I();201}202203SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_yaw, new_servo_out);204205if (yaw_servo_out_filt_init) {206yaw_servo_out_filt.apply(new_servo_out, G_Dt);207} else {208yaw_servo_out_filt.reset(new_servo_out);209yaw_servo_out_filt_init = true;210}211}212213214/**215update the yaw (azimuth) servo. The aim is to drive the boards ahrs216yaw to the requested yaw, so the board (and therefore the antenna)217will be pointing at the target218*/219void Tracker::update_yaw_onoff_servo(float yaw) const220{221float acceptable_error = g.onoff_yaw_rate * g.onoff_yaw_mintime;222if (fabsf(nav_status.angle_error_yaw * 0.01f) < acceptable_error) {223SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_yaw, 0);224} else if (nav_status.angle_error_yaw * 0.01f > 0) {225// positive error means we are counter-clockwise of the target, so226// move clockwise227SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_yaw, 18000);228} else {229// negative error means we are clockwise of the target, so230// move counter-clockwise231SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_yaw, -18000);232}233}234235/**236update the yaw continuous rotation servo237*/238void Tracker::update_yaw_cr_servo(float yaw)239{240const 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);241SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_yaw, yaw_out);242}243244245