mirror of https://github.com/ArduPilot/ardupilot
AP_Camera: add change settings
This commit is contained in:
parent
1f0c31bcef
commit
78d88d11a3
|
@ -780,6 +780,19 @@ bool AP_Camera::get_state(uint8_t instance, camera_state_t& cam_state)
|
||||||
}
|
}
|
||||||
return backend->get_state(cam_state);
|
return backend->get_state(cam_state);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// change camera settings not normally used by autopilot
|
||||||
|
bool AP_Camera::change_setting(uint8_t instance, CameraSetting setting, float value)
|
||||||
|
{
|
||||||
|
WITH_SEMAPHORE(_rsem);
|
||||||
|
|
||||||
|
auto *backend = get_instance(instance);
|
||||||
|
if (backend == nullptr) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return backend->change_setting(setting, value);
|
||||||
|
}
|
||||||
|
|
||||||
#endif // #if AP_CAMERA_SCRIPTING_ENABLED
|
#endif // #if AP_CAMERA_SCRIPTING_ENABLED
|
||||||
|
|
||||||
// return backend for instance number
|
// return backend for instance number
|
||||||
|
|
|
@ -181,6 +181,9 @@ public:
|
||||||
// accessor to allow scripting backend to retrieve state
|
// accessor to allow scripting backend to retrieve state
|
||||||
// returns true on success and cam_state is filled in
|
// returns true on success and cam_state is filled in
|
||||||
bool get_state(uint8_t instance, camera_state_t& cam_state);
|
bool get_state(uint8_t instance, camera_state_t& cam_state);
|
||||||
|
|
||||||
|
// change camera settings not normally used by autopilot
|
||||||
|
bool change_setting(uint8_t instance, CameraSetting setting, float value);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Return true and the relay index if relay camera backend is selected, used for conversion to relay functions
|
// Return true and the relay index if relay camera backend is selected, used for conversion to relay functions
|
||||||
|
|
|
@ -130,6 +130,9 @@ public:
|
||||||
// accessor to allow scripting backend to retrieve state
|
// accessor to allow scripting backend to retrieve state
|
||||||
// returns true on success and cam_state is filled in
|
// returns true on success and cam_state is filled in
|
||||||
virtual bool get_state(AP_Camera::camera_state_t& cam_state) { return false; }
|
virtual bool get_state(AP_Camera::camera_state_t& cam_state) { return false; }
|
||||||
|
|
||||||
|
// change camera settings not normally used by autopilot
|
||||||
|
virtual bool change_setting(CameraSetting setting, float value) { return false; }
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
|
@ -109,4 +109,16 @@ void AP_Camera_Mount::send_camera_capture_status(mavlink_channel_t chan) const
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_CAMERA_SCRIPTING_ENABLED
|
||||||
|
// change camera settings not normally used by autopilot
|
||||||
|
bool AP_Camera_Mount::change_setting(CameraSetting setting, float value)
|
||||||
|
{
|
||||||
|
AP_Mount* mount = AP::mount();
|
||||||
|
if (mount != nullptr) {
|
||||||
|
return mount->change_setting(get_mount_instance(), setting, value);
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // AP_CAMERA_MOUNT_ENABLED
|
#endif // AP_CAMERA_MOUNT_ENABLED
|
||||||
|
|
|
@ -69,6 +69,11 @@ public:
|
||||||
|
|
||||||
// send camera capture status message to GCS
|
// send camera capture status message to GCS
|
||||||
void send_camera_capture_status(mavlink_channel_t chan) const override;
|
void send_camera_capture_status(mavlink_channel_t chan) const override;
|
||||||
|
|
||||||
|
#if AP_CAMERA_SCRIPTING_ENABLED
|
||||||
|
// change camera settings not normally used by autopilot
|
||||||
|
bool change_setting(CameraSetting setting, float value) override;
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_CAMERA_MOUNT_ENABLED
|
#endif // AP_CAMERA_MOUNT_ENABLED
|
||||||
|
|
|
@ -36,3 +36,9 @@ enum class TrackingType : uint8_t {
|
||||||
TRK_RECTANGLE = 2 // tracking a rectangle
|
TRK_RECTANGLE = 2 // tracking a rectangle
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// camera settings not normally used by the autopilot
|
||||||
|
enum class CameraSetting {
|
||||||
|
THERMAL_PALETTE = 0, // set thermal palette
|
||||||
|
THERMAL_GAIN = 1, // set thermal gain, value of 0:low gain, 1:high gain
|
||||||
|
THERMAL_RAW_DATA = 2, // enable/disable thermal raw data
|
||||||
|
};
|
||||||
|
|
Loading…
Reference in New Issue