Browse Source

AP_Camera: make AP_Camera::control() return bool for picture trigger

this allows a picture to be logged if it is requested
mission-4.1.18
Andrew Tridgell 9 years ago
parent
commit
dc998a2eaf
  1. 6
      libraries/AP_Camera/AP_Camera.cpp
  2. 3
      libraries/AP_Camera/AP_Camera.h

6
libraries/AP_Camera/AP_Camera.cpp

@ -210,11 +210,14 @@ void AP_Camera::configure(float shooting_mode, float shutter_speed, float apertu @@ -210,11 +210,14 @@ void AP_Camera::configure(float shooting_mode, float shutter_speed, float apertu
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
if (is_equal(shooting_cmd,1.0f)) {
trigger_pic(false);
ret = true;
}
mavlink_message_t msg;
@ -234,6 +237,7 @@ void AP_Camera::control(float session, float zoom_pos, float zoom_step, float fo @@ -234,6 +237,7 @@ void AP_Camera::control(float session, float zoom_pos, float zoom_step, float fo
// send to all components
GCS_MAVLINK::send_to_components(&msg);
return ret;
}
/*

3
libraries/AP_Camera/AP_Camera.h

@ -56,7 +56,8 @@ public: @@ -56,7 +56,8 @@ public:
// 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 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
void set_trigger_distance(uint32_t distance_m) { _trigg_dist.set(distance_m); }

Loading…
Cancel
Save