mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: add get_camera_state method
This commit is contained in:
parent
6678689312
commit
04e8fffc53
|
@ -469,6 +469,14 @@ void AP_Mount::set_attitude_euler(uint8_t instance, float roll_deg, float pitch_
|
|||
_backends[instance]->set_attitude_euler(roll_deg, pitch_deg, yaw_bf_deg);
|
||||
}
|
||||
|
||||
bool AP_Mount::get_camera_state(uint8_t instance, uint16_t& pic_count, bool& record_video, int8_t& zoom_step, int8_t& focus_step, bool& auto_focus)
|
||||
{
|
||||
if (!check_instance(instance)) {
|
||||
return false;
|
||||
}
|
||||
return _backends[instance]->get_camera_state(pic_count, record_video, zoom_step, focus_step, auto_focus);
|
||||
}
|
||||
|
||||
// point at system ID sysid
|
||||
void AP_Mount::set_target_sysid(uint8_t instance, uint8_t sysid)
|
||||
{
|
||||
|
|
|
@ -172,6 +172,7 @@ public:
|
|||
bool get_angle_target(uint8_t instance, float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame);
|
||||
bool get_location_target(uint8_t instance, Location& target_loc);
|
||||
void set_attitude_euler(uint8_t instance, float roll_deg, float pitch_deg, float yaw_bf_deg);
|
||||
bool get_camera_state(uint8_t instance, uint16_t& pic_count, bool& record_video, int8_t& zoom_step, int8_t& focus_step, bool& auto_focus);
|
||||
|
||||
//
|
||||
// camera controls for gimbals that include a camera
|
||||
|
|
|
@ -109,6 +109,7 @@ public:
|
|||
virtual bool get_angle_target(float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame) { return false; }
|
||||
virtual bool get_location_target(Location &target_loc) { return false; }
|
||||
virtual void set_attitude_euler(float roll_deg, float pitch_deg, float yaw_bf_deg) {};
|
||||
virtual bool get_camera_state(uint16_t& pic_count, bool& record_video, int8_t& zoom_step, int8_t& focus_step, bool& auto_focus) { return false; }
|
||||
|
||||
//
|
||||
// camera controls for gimbals that include a camera
|
||||
|
|
|
@ -222,6 +222,16 @@ 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)
|
||||
{
|
||||
|
|
|
@ -61,6 +61,7 @@ public:
|
|||
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:
|
||||
|
||||
|
|
Loading…
Reference in New Issue