mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
AP_Camera: constify get_instance
This commit is contained in:
parent
5d29935039
commit
58b73c3613
@ -431,7 +431,7 @@ bool AP_Camera::set_auto_focus(uint8_t instance)
|
||||
}
|
||||
|
||||
// return backend for instance number
|
||||
AP_Camera_Backend *AP_Camera::get_instance(uint8_t instance)
|
||||
AP_Camera_Backend *AP_Camera::get_instance(uint8_t instance) const
|
||||
{
|
||||
if (instance >= ARRAY_SIZE(_backends)) {
|
||||
return nullptr;
|
||||
|
@ -150,7 +150,7 @@ private:
|
||||
AP_Int16 _max_roll; // Maximum acceptable roll angle when trigging camera
|
||||
|
||||
// check instance number is valid
|
||||
AP_Camera_Backend *get_instance(uint8_t instance);
|
||||
AP_Camera_Backend *get_instance(uint8_t instance) const;
|
||||
|
||||
// perform any required parameter conversion
|
||||
void convert_params();
|
||||
|
Loading…
Reference in New Issue
Block a user