mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 10:13:57 -04:00
AP_Camera: make AP_Camera::control() return bool for picture trigger
this allows a picture to be logged if it is requested
This commit is contained in:
parent
2099f40d89
commit
dc998a2eaf
@ -210,11 +210,14 @@ void AP_Camera::configure(float shooting_mode, float shutter_speed, float apertu
|
|||||||
GCS_MAVLINK::send_to_components(&msg);
|
GCS_MAVLINK::send_to_components(&msg);
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_Camera::control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id)
|
bool AP_Camera::control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id)
|
||||||
{
|
{
|
||||||
|
bool ret = false;
|
||||||
|
|
||||||
// take picture
|
// take picture
|
||||||
if (is_equal(shooting_cmd,1.0f)) {
|
if (is_equal(shooting_cmd,1.0f)) {
|
||||||
trigger_pic(false);
|
trigger_pic(false);
|
||||||
|
ret = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
mavlink_message_t msg;
|
mavlink_message_t msg;
|
||||||
@ -234,6 +237,7 @@ void AP_Camera::control(float session, float zoom_pos, float zoom_step, float fo
|
|||||||
|
|
||||||
// send to all components
|
// send to all components
|
||||||
GCS_MAVLINK::send_to_components(&msg);
|
GCS_MAVLINK::send_to_components(&msg);
|
||||||
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -56,7 +56,8 @@ public:
|
|||||||
|
|
||||||
// Command processing
|
// Command processing
|
||||||
void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time);
|
void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time);
|
||||||
void control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id);
|
// handle camera control. Return true if picture was triggered
|
||||||
|
bool control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id);
|
||||||
|
|
||||||
// set camera trigger distance in a mission
|
// set camera trigger distance in a mission
|
||||||
void set_trigger_distance(uint32_t distance_m) { _trigg_dist.set(distance_m); }
|
void set_trigger_distance(uint32_t distance_m) { _trigg_dist.set(distance_m); }
|
||||||
|
Loading…
Reference in New Issue
Block a user