mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_Mount: add set_tracking accessor
This commit is contained in:
parent
471f528233
commit
ddb91afdde
@ -751,6 +751,18 @@ SetFocusResult AP_Mount::set_focus(uint8_t instance, FocusType focus_type, float
|
||||
return backend->set_focus(focus_type, focus_value);
|
||||
}
|
||||
|
||||
// set tracking to none, point or rectangle (see TrackingType enum)
|
||||
// if POINT only p1 is used, if RECTANGLE then p1 is top-left, p2 is bottom-right
|
||||
// p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom
|
||||
bool AP_Mount::set_tracking(uint8_t instance, TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2)
|
||||
{
|
||||
auto *backend = get_instance(instance);
|
||||
if (backend == nullptr) {
|
||||
return false;
|
||||
}
|
||||
return backend->set_tracking(tracking_type, p1, p2);
|
||||
}
|
||||
|
||||
// send camera information message to GCS
|
||||
void AP_Mount::send_camera_information(mavlink_channel_t chan) const
|
||||
{
|
||||
|
@ -218,6 +218,11 @@ public:
|
||||
// focus in = -1, focus hold = 0, focus out = 1
|
||||
SetFocusResult set_focus(uint8_t instance, FocusType focus_type, float focus_value);
|
||||
|
||||
// set tracking to none, point or rectangle (see TrackingType enum)
|
||||
// if POINT only p1 is used, if RECTANGLE then p1 is top-left, p2 is bottom-right
|
||||
// p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom
|
||||
bool set_tracking(uint8_t instance, TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2);
|
||||
|
||||
// send camera information message to GCS
|
||||
void send_camera_information(mavlink_channel_t chan) const;
|
||||
|
||||
|
@ -157,6 +157,11 @@ public:
|
||||
// focus in = -1, focus hold = 0, focus out = 1
|
||||
virtual SetFocusResult set_focus(FocusType focus_type, float focus_value) { return SetFocusResult::UNSUPPORTED; }
|
||||
|
||||
// set tracking to none, point or rectangle (see TrackingType enum)
|
||||
// if POINT only p1 is used, if RECTANGLE then p1 is top-left, p2 is bottom-right
|
||||
// p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom
|
||||
virtual bool set_tracking(TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2) { return false; }
|
||||
|
||||
// send camera information message to GCS
|
||||
virtual void send_camera_information(mavlink_channel_t chan) const {}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user