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/tracking.cpp
Views: 1798
#include "Tracker.h"12/**3update_vehicle_position_estimate - updates estimate of vehicle positions4should be called at 50hz5*/6void Tracker::update_vehicle_pos_estimate()7{8// calculate time since last actual position update9float dt = (AP_HAL::micros() - vehicle.last_update_us) * 1.0e-6f;1011// if less than 5 seconds since last position update estimate the position12if (dt < TRACKING_TIMEOUT_SEC) {13// project the vehicle position to take account of lost radio packets14vehicle.location_estimate = vehicle.location;15float north_offset = vehicle.vel.x * dt;16float east_offset = vehicle.vel.y * dt;17vehicle.location_estimate.offset(north_offset, east_offset);18vehicle.location_estimate.alt += vehicle.vel.z * 100.0f * dt;19// set valid_location flag20vehicle.location_valid = true;21} else {22// vehicle has been lost, set lost flag23vehicle.location_valid = false;24}25}2627/**28update_tracker_position - updates antenna tracker position from GPS location29should be called at 50hz30*/31void Tracker::update_tracker_position()32{33Location temp_loc;3435// REVISIT: what if we lose lock during a mission and the antenna is moving?36if (ahrs.get_location(temp_loc)) {37stationary = false;38current_loc = temp_loc;39}40}4142/**43update_bearing_and_distance - updates bearing and distance to the vehicle44should be called at 50hz45*/46void Tracker::update_bearing_and_distance()47{48// exit immediately if we do not have a valid vehicle position49if (!vehicle.location_valid) {50return;51}5253// calculate bearing to vehicle54// To-Do: remove need for check of control_mode55if (mode != &mode_scan && !nav_status.manual_control_yaw) {56nav_status.bearing = current_loc.get_bearing_to(vehicle.location_estimate) * 0.01f;57}5859// calculate distance to vehicle60nav_status.distance = current_loc.get_distance(vehicle.location_estimate);6162// calculate altitude difference to vehicle using gps63if (g.alt_source == ALT_SOURCE_GPS){64nav_status.alt_difference_gps = (vehicle.location_estimate.alt - current_loc.alt) * 0.01f;65} else {66// g.alt_source == ALT_SOURCE_GPS_VEH_ONLY67nav_status.alt_difference_gps = vehicle.relative_alt * 0.01f;68}6970// calculate pitch to vehicle71// To-Do: remove need for check of control_mode72if (mode->number() != Mode::Number::SCAN && !nav_status.manual_control_pitch) {73if (g.alt_source == ALT_SOURCE_BARO) {74nav_status.pitch = degrees(atan2f(nav_status.alt_difference_baro, nav_status.distance));75} else {76nav_status.pitch = degrees(atan2f(nav_status.alt_difference_gps, nav_status.distance));77}78}79}8081/**82main antenna tracking code, called at 50Hz83*/84void Tracker::update_tracking(void)85{86// update vehicle position estimate87update_vehicle_pos_estimate();8889// update antenna tracker position from GPS90update_tracker_position();9192// update bearing and distance to vehicle93update_bearing_and_distance();9495// do not perform any servo updates until startup delay has passed96if (g.startup_delay > 0 &&97AP_HAL::millis() - start_time_ms < g.startup_delay*1000) {98return;99}100101// do not perform updates if safety switch is disarmed (i.e. servos can't be moved)102if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {103return;104}105// do not move if we are not armed:106if (!hal.util->get_soft_armed()) {107switch ((PWMDisarmed)g.disarm_pwm.get()) {108case PWMDisarmed::TRIM:109SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_yaw, 0);110SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_pitch, 0);111break;112default:113case PWMDisarmed::ZERO:114SRV_Channels::set_output_pwm(SRV_Channel::k_tracker_yaw, 0);115SRV_Channels::set_output_pwm(SRV_Channel::k_tracker_pitch, 0);116break;117}118} else {119mode->update();120}121122// convert servo_out to radio_out and send to servo123SRV_Channels::calc_pwm();124SRV_Channels::output_ch_all();125return;126}127128/**129handle an updated position from the aircraft130*/131void Tracker::tracking_update_position(const mavlink_global_position_int_t &msg)132{133// reject (0;0) coordinates134if (!msg.lat && !msg.lon) {135return;136}137138vehicle.location.lat = msg.lat;139vehicle.location.lng = msg.lon;140vehicle.location.alt = msg.alt/10;141vehicle.relative_alt = msg.relative_alt/10;142vehicle.vel = Vector3f(msg.vx*0.01f, msg.vy*0.01f, msg.vz*0.01f);143vehicle.last_update_us = AP_HAL::micros();144vehicle.last_update_ms = AP_HAL::millis();145#if HAL_LOGGING_ENABLED146// log vehicle as VPOS147if (should_log(MASK_LOG_GPS)) {148Log_Write_Vehicle_Pos(vehicle.location.lat, vehicle.location.lng, vehicle.location.alt, vehicle.vel);149}150#endif151}152153154/**155handle an updated pressure reading from the aircraft156*/157void Tracker::tracking_update_pressure(const mavlink_scaled_pressure_t &msg)158{159float local_pressure = barometer.get_pressure();160float aircraft_pressure = msg.press_abs*100.0f;161162// calculate altitude difference based on difference in barometric pressure163float alt_diff = barometer.get_altitude_difference(local_pressure, aircraft_pressure);164if (!isnan(alt_diff) && !isinf(alt_diff)) {165nav_status.alt_difference_baro = alt_diff + nav_status.altitude_offset;166167if (nav_status.need_altitude_calibration) {168// we have done a baro calibration - zero the altitude169// difference to the aircraft170nav_status.altitude_offset = -alt_diff;171nav_status.alt_difference_baro = 0;172nav_status.need_altitude_calibration = false;173}174}175176#if HAL_LOGGING_ENABLED177// log vehicle baro data178Log_Write_Vehicle_Baro(aircraft_pressure, alt_diff);179#endif180}181182/**183handle a manual control message by using the data to command yaw and pitch184*/185void Tracker::tracking_manual_control(const mavlink_manual_control_t &msg)186{187nav_status.bearing = msg.x;188nav_status.pitch = msg.y;189nav_status.distance = 0.0;190nav_status.manual_control_yaw = (msg.x != 0x7FFF);191nav_status.manual_control_pitch = (msg.y != 0x7FFF);192// z, r and buttons are not used193}194195/**196update_armed_disarmed - set armed LED if we have received a position update within the last 5 seconds197*/198void Tracker::update_armed_disarmed() const199{200if (vehicle.last_update_ms != 0 && (AP_HAL::millis() - vehicle.last_update_ms) < TRACKING_TIMEOUT_MS) {201AP_Notify::flags.armed = true;202} else {203AP_Notify::flags.armed = false;204}205}206207/*208Returns the pan and tilt for use by onvif camera in scripting209the output will be mapped to -1..1 from limits specified by PITCH_MIN210and PITCH_MAX for tilt, and YAW_RANGE for pan211*/212bool Tracker::get_pan_tilt_norm(float &pan_norm, float &tilt_norm) const213{214float pitch = nav_status.pitch;215float bearing = nav_status.bearing;216// set tilt value217tilt_norm = (((constrain_float(pitch+g.pitch_trim, g.pitch_min, g.pitch_max) - g.pitch_min)*2.0f)/(g.pitch_max - g.pitch_min)) - 1;218// set yaw value219pan_norm = (wrap_360(bearing+g.yaw_trim)*2.0f/(g.yaw_range)) - 1;220return true;221}222223224