mirror of https://github.com/ArduPilot/ardupilot
AP_Camera: support send-thermal-range
This commit is contained in:
parent
2db7a9520a
commit
6f2a88f707
|
@ -461,6 +461,12 @@ bool AP_Camera::send_mavlink_message(GCS_MAVLINK &link, const enum ap_message ms
|
||||||
CHECK_PAYLOAD_SIZE2(CAMERA_CAPTURE_STATUS);
|
CHECK_PAYLOAD_SIZE2(CAMERA_CAPTURE_STATUS);
|
||||||
send_camera_capture_status(chan);
|
send_camera_capture_status(chan);
|
||||||
break;
|
break;
|
||||||
|
#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED
|
||||||
|
case MSG_CAMERA_THERMAL_RANGE:
|
||||||
|
CHECK_PAYLOAD_SIZE2(CAMERA_THERMAL_RANGE);
|
||||||
|
send_camera_thermal_range(chan);
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
|
||||||
default:
|
default:
|
||||||
// should not reach this; should only be called for specific IDs
|
// should not reach this; should only be called for specific IDs
|
||||||
|
@ -615,6 +621,21 @@ void AP_Camera::send_camera_capture_status(mavlink_channel_t chan)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED
|
||||||
|
// send camera thermal range message to GCS
|
||||||
|
void AP_Camera::send_camera_thermal_range(mavlink_channel_t chan)
|
||||||
|
{
|
||||||
|
WITH_SEMAPHORE(_rsem);
|
||||||
|
|
||||||
|
// call each instance
|
||||||
|
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
|
||||||
|
if (_backends[instance] != nullptr) {
|
||||||
|
_backends[instance]->send_camera_thermal_range(chan);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
update; triggers by distance moved and camera trigger
|
update; triggers by distance moved and camera trigger
|
||||||
*/
|
*/
|
||||||
|
|
|
@ -240,6 +240,11 @@ private:
|
||||||
// send camera capture status message to GCS
|
// send camera capture status message to GCS
|
||||||
void send_camera_capture_status(mavlink_channel_t chan);
|
void send_camera_capture_status(mavlink_channel_t chan);
|
||||||
|
|
||||||
|
#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED
|
||||||
|
// send camera thermal range message to GCS
|
||||||
|
void send_camera_thermal_range(mavlink_channel_t chan);
|
||||||
|
#endif
|
||||||
|
|
||||||
HAL_Semaphore _rsem; // semaphore for multi-thread access
|
HAL_Semaphore _rsem; // semaphore for multi-thread access
|
||||||
AP_Camera_Backend *primary; // primary camera backed
|
AP_Camera_Backend *primary; // primary camera backed
|
||||||
bool _is_in_auto_mode; // true if in AUTO mode
|
bool _is_in_auto_mode; // true if in AUTO mode
|
||||||
|
|
|
@ -126,6 +126,11 @@ public:
|
||||||
// send camera capture status message to GCS
|
// send camera capture status message to GCS
|
||||||
virtual void send_camera_capture_status(mavlink_channel_t chan) const;
|
virtual void send_camera_capture_status(mavlink_channel_t chan) const;
|
||||||
|
|
||||||
|
#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED
|
||||||
|
// send camera thermal range message to GCS
|
||||||
|
virtual void send_camera_thermal_range(mavlink_channel_t chan) const {};
|
||||||
|
#endif
|
||||||
|
|
||||||
#if AP_CAMERA_SCRIPTING_ENABLED
|
#if AP_CAMERA_SCRIPTING_ENABLED
|
||||||
// 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
|
||||||
|
|
|
@ -109,6 +109,19 @@ void AP_Camera_Mount::send_camera_capture_status(mavlink_channel_t chan) const
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED
|
||||||
|
// send camera thermal range message to GCS
|
||||||
|
void AP_Camera_Mount::send_camera_thermal_range(mavlink_channel_t chan) const
|
||||||
|
{
|
||||||
|
#if AP_MOUNT_SEND_THERMAL_RANGE_ENABLED
|
||||||
|
AP_Mount* mount = AP::mount();
|
||||||
|
if (mount != nullptr) {
|
||||||
|
mount->send_camera_thermal_range(get_mount_instance(), chan);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif // AP_CAMERA_SEND_THERMAL_RANGE_ENABLED
|
||||||
|
|
||||||
#if AP_CAMERA_SCRIPTING_ENABLED
|
#if AP_CAMERA_SCRIPTING_ENABLED
|
||||||
// change camera settings not normally used by autopilot
|
// change camera settings not normally used by autopilot
|
||||||
bool AP_Camera_Mount::change_setting(CameraSetting setting, float value)
|
bool AP_Camera_Mount::change_setting(CameraSetting setting, float value)
|
||||||
|
|
|
@ -70,6 +70,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_SEND_THERMAL_RANGE_ENABLED
|
||||||
|
// send camera thermal range message to GCS
|
||||||
|
void send_camera_thermal_range(mavlink_channel_t chan) const override;
|
||||||
|
#endif
|
||||||
|
|
||||||
#if AP_CAMERA_SCRIPTING_ENABLED
|
#if AP_CAMERA_SCRIPTING_ENABLED
|
||||||
// change camera settings not normally used by autopilot
|
// change camera settings not normally used by autopilot
|
||||||
bool change_setting(CameraSetting setting, float value) override;
|
bool change_setting(CameraSetting setting, float value) override;
|
||||||
|
|
|
@ -50,6 +50,11 @@
|
||||||
#define AP_CAMERA_SET_CAMERA_SOURCE_ENABLED HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED
|
#define AP_CAMERA_SET_CAMERA_SOURCE_ENABLED HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// send thermal range is supported on a few thermal cameras but all are within mounts
|
||||||
|
#ifndef AP_CAMERA_SEND_THERMAL_RANGE_ENABLED
|
||||||
|
#define AP_CAMERA_SEND_THERMAL_RANGE_ENABLED AP_MOUNT_SEND_THERMAL_RANGE_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef HAL_RUNCAM_ENABLED
|
#ifndef HAL_RUNCAM_ENABLED
|
||||||
#define HAL_RUNCAM_ENABLED 1
|
#define HAL_RUNCAM_ENABLED 1
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue