AP_Mount: Siyi implements change_setting

This commit is contained in:
Randy Mackay 2024-08-23 20:59:14 +09:00
parent 78d88d11a3
commit 1f14c2ca6b
5 changed files with 46 additions and 0 deletions

View File

@ -907,6 +907,17 @@ void AP_Mount::send_camera_capture_status(uint8_t instance, mavlink_channel_t ch
backend->send_camera_capture_status(chan);
}
// change camera settings not normally used by autopilot
// setting values from AP_Camera::Setting enum
bool AP_Mount::change_setting(uint8_t instance, CameraSetting setting, float value)
{
auto *backend = get_instance(instance);
if (backend == nullptr) {
return false;
}
return backend->change_setting(setting, value);
}
// get rangefinder distance. Returns true on success
bool AP_Mount::get_rangefinder_distance(uint8_t instance, float& distance_m) const
{

View File

@ -271,6 +271,10 @@ public:
// send camera capture status message to GCS
void send_camera_capture_status(uint8_t instance, mavlink_channel_t chan) const;
// change camera settings not normally used by autopilot
// setting values from AP_Camera::Setting enum
bool change_setting(uint8_t instance, CameraSetting setting, float value);
//
// rangefinder
//

View File

@ -198,6 +198,9 @@ public:
// send camera capture status message to GCS
virtual void send_camera_capture_status(mavlink_channel_t chan) const {}
// change camera settings not normally used by autopilot
virtual bool change_setting(CameraSetting setting, float value) { return false; }
#if AP_MOUNT_POI_TO_LATLONALT_ENABLED
// get poi information. Returns true on success and fills in gimbal attitude, location and poi location
bool get_poi(uint8_t instance, Quaternion &quat, Location &loc, Location &poi_loc);

View File

@ -1098,6 +1098,25 @@ void AP_Mount_Siyi::send_camera_settings(mavlink_channel_t chan) const
NaN); // focusLevel float, percentage from 0 to 100, NaN if unknown
}
// change camera settings not normally used by autopilot
// THERMAL_PALETTE: 0:WhiteHot, 2:Sepia, 3:IronBow, 4:Rainbow, 5:Night, 6:Aurora, 7:RedHot, 8:Jungle, 9:Medical, 10:BlackHot, 11:GloryHot
// THERMAL_GAIN: 0:Low gain (50C ~ 550C), 1:High gain (-20C ~ 150C)
// THERMAL_RAW_DATA: 0:Disable Raw Data (30fps), 1:Enable Raw Data (25fps)
bool AP_Mount_Siyi::change_setting(CameraSetting setting, float value)
{
switch (setting) {
case CameraSetting::THERMAL_PALETTE:
return send_1byte_packet(SiyiCommandId::SET_THERMAL_PALETTE, (uint8_t)value);
case CameraSetting::THERMAL_GAIN:
return send_1byte_packet(SiyiCommandId::SET_THERMAL_GAIN, (uint8_t)value);
case CameraSetting::THERMAL_RAW_DATA:
return send_1byte_packet(SiyiCommandId::SET_THERMAL_RAW_DATA, (uint8_t)value);
}
// invalid setting so return false
return false;
}
// get model name string. returns "Unknown" if hardware model is not yet known
const char* AP_Mount_Siyi::get_model_name() const
{

View File

@ -82,6 +82,12 @@ public:
// send camera settings message to GCS
void send_camera_settings(mavlink_channel_t chan) const override;
// change camera settings not normally used by autopilot
// THERMAL_PALETTE: 0:WhiteHot, 2:Sepia, 3:IronBow, 4:Rainbow, 5:Night, 6:Aurora, 7:RedHot, 8:Jungle, 9:Medical, 10:BlackHot, 11:GloryHot
// THERMAL_GAIN: 0:Low gain (50C ~ 550C), 1:High gain (-20C ~ 150C)
// THERMAL_RAW_DATA: 0:Disable Raw Data (30fps), 1:Enable Raw Data (25fps)
bool change_setting(CameraSetting setting, float value) override;
//
// rangefinder
//
@ -118,8 +124,11 @@ private:
ABSOLUTE_ZOOM = 0x0F,
SET_CAMERA_IMAGE_TYPE = 0x11,
READ_RANGEFINDER = 0x15,
SET_THERMAL_PALETTE = 0x1B,
EXTERNAL_ATTITUDE = 0x22,
SET_TIME = 0x30,
SET_THERMAL_RAW_DATA = 0x34,
SET_THERMAL_GAIN = 0x38,
POSITION_DATA = 0x3e,
};