mirror of https://github.com/ArduPilot/ardupilot
AntennaTracker: add support for controlling ONVIF camera using lua script
This commit is contained in:
parent
f6715cdaa0
commit
cd63dd1720
|
@ -232,6 +232,7 @@ private:
|
|||
void tracking_update_pressure(const mavlink_scaled_pressure_t &msg);
|
||||
void tracking_manual_control(const mavlink_manual_control_t &msg);
|
||||
void update_armed_disarmed() const;
|
||||
bool get_pan_tilt_norm(float &pan_norm, float &tilt_norm) const override;
|
||||
|
||||
// Arming/Disarming management class
|
||||
AP_Arming_Tracker arming;
|
||||
|
|
|
@ -195,3 +195,19 @@ void Tracker::update_armed_disarmed() const
|
|||
AP_Notify::flags.armed = false;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
Returns the pan and tilt for use by onvif camera in scripting
|
||||
the output will be mapped to -1..1 from limits specified by PITCH_MIN
|
||||
and PITCH_MAX for tilt, and YAW_RANGE for pan
|
||||
*/
|
||||
bool Tracker::get_pan_tilt_norm(float &pan_norm, float &tilt_norm) const
|
||||
{
|
||||
float pitch = nav_status.pitch;
|
||||
float bearing = nav_status.bearing;
|
||||
// set tilt value
|
||||
tilt_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;
|
||||
// set yaw value
|
||||
pan_norm = (wrap_360(bearing+g.yaw_trim)*2.0f/(g.yaw_range)) - 1;
|
||||
return true;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue