AP_Mount: scripting backend loses camera support

drivers should use the camera scripting backend
This commit is contained in:
Randy Mackay 2023-04-08 12:40:16 +09:00 committed by Peter Barker
parent 1a375f1ff5
commit db51915e27
2 changed files with 0 additions and 77 deletions

View File

@ -136,47 +136,6 @@ bool AP_Mount_Scripting::healthy() const
return (AP_HAL::millis() - last_update_ms <= AP_MOUNT_SCRIPTING_TIMEOUT_MS);
}
// take a picture. returns true on success
bool AP_Mount_Scripting::take_picture()
{
picture_count++;
recording_video = false;
return true;
}
// start or stop video recording. returns true on success
// set start_recording = true to start record, false to stop recording
bool AP_Mount_Scripting::record_video(bool start_recording)
{
recording_video = start_recording;
return true;
}
// set camera zoom step. returns true on success
// zoom out = -1, hold = 0, zoom in = 1
bool AP_Mount_Scripting::set_zoom_step(int8_t zoom_step)
{
manual_zoom_step = zoom_step;
return true;
}
// set focus in, out or hold. returns true on success
// focus in = -1, focus hold = 0, focus out = 1
bool AP_Mount_Scripting::set_manual_focus_step(int8_t focus_step)
{
manual_focus_step = focus_step;
auto_focus_active = false;
return true;
}
// auto focus. returns true on success
bool AP_Mount_Scripting::set_auto_focus()
{
manual_focus_step = 0;
auto_focus_active = true;
return true;
}
// accessors for scripting backends
bool AP_Mount_Scripting::get_rate_target(float& roll_degs, float& pitch_degs, float& yaw_degs, bool& yaw_is_earth_frame)
{
@ -222,16 +181,6 @@ void AP_Mount_Scripting::set_attitude_euler(float roll_deg, float pitch_deg, flo
current_angle_deg.z = yaw_bf_deg;
}
bool AP_Mount_Scripting::get_camera_state(uint16_t& pic_count, bool& record_video, int8_t& zoom_step, int8_t& focus_step, bool& auto_focus)
{
pic_count = picture_count;
record_video = recording_video;
zoom_step = manual_zoom_step;
focus_step = manual_focus_step;
auto_focus = auto_focus_active;
return true;
}
// get attitude as a quaternion. returns true on success
bool AP_Mount_Scripting::get_attitude_quaternion(Quaternion& att_quat)
{

View File

@ -34,30 +34,11 @@ public:
// has_pan_control - returns true if this mount can control its pan (required for multicopters)
bool has_pan_control() const override { return yaw_range_valid(); };
// take a picture. returns true on success
bool take_picture() override;
// start or stop video recording. returns true on success
// set start_recording = true to start record, false to stop recording
bool record_video(bool start_recording) override;
// set camera zoom step. returns true on success
// zoom out = -1, hold = 0, zoom in = 1
bool set_zoom_step(int8_t zoom_step) override;
// set focus in, out or hold. returns true on success
// focus in = -1, focus hold = 0, focus out = 1
bool set_manual_focus_step(int8_t focus_step) override;
// auto focus. returns true on success
bool set_auto_focus() override;
// accessors for scripting backends
bool get_rate_target(float& roll_degs, float& pitch_degs, float& yaw_degs, bool& yaw_is_earth_frame) override;
bool get_angle_target(float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame) override;
bool get_location_target(Location& _target_loc) override;
void set_attitude_euler(float roll_deg, float pitch_deg, float yaw_bf_deg) override;
bool get_camera_state(uint16_t& pic_count, bool& record_video, int8_t& zoom_step, int8_t& focus_step, bool& auto_focus) override;
protected:
@ -78,13 +59,6 @@ private:
Location target_loc; // target location
bool target_loc_valid; // true if target_loc holds a valid target location
// camera related internal variables
uint16_t picture_count; // number of pictures that have been taken (or at least requested)
bool recording_video; // true when record video has been requested
int8_t manual_zoom_step; // manual zoom step. zoom out = -1, hold = 0, zoom in = 1
int8_t manual_focus_step; // manual focus step. focus in = -1, focus hold = 0, focus out = 1
bool auto_focus_active; // auto focus active
};
#endif // HAL_MOUNT_SIYISERIAL_ENABLED