mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Mount: add set lens support
This commit is contained in:
parent
1dc1d24f1e
commit
315d972c5d
@ -794,6 +794,16 @@ bool AP_Mount::set_tracking(uint8_t instance, TrackingType tracking_type, const
|
||||
return backend->set_tracking(tracking_type, p1, p2);
|
||||
}
|
||||
|
||||
// set camera lens as a value from 0 to 5
|
||||
bool AP_Mount::set_lens(uint8_t instance, uint8_t lens)
|
||||
{
|
||||
auto *backend = get_instance(instance);
|
||||
if (backend == nullptr) {
|
||||
return false;
|
||||
}
|
||||
return backend->set_lens(lens);
|
||||
}
|
||||
|
||||
// send camera information message to GCS
|
||||
void AP_Mount::send_camera_information(mavlink_channel_t chan) const
|
||||
{
|
||||
|
@ -238,6 +238,9 @@ public:
|
||||
// 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);
|
||||
|
||||
// set camera lens as a value from 0 to 5
|
||||
bool set_lens(uint8_t instance, uint8_t lens);
|
||||
|
||||
// send camera information message to GCS
|
||||
void send_camera_information(mavlink_channel_t chan) const;
|
||||
|
||||
|
@ -169,6 +169,9 @@ public:
|
||||
// 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; }
|
||||
|
||||
// set camera lens as a value from 0 to 5
|
||||
virtual bool set_lens(uint8_t lens) { 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