Copter: camera is responsible for taking distance-based-images and logging

This commit is contained in:
Peter Barker 2017-07-26 13:33:45 +10:00 committed by Francisco Ferreira
parent 81d52c282c
commit cdf9ebcb39
6 changed files with 17 additions and 58 deletions

View File

@ -338,13 +338,7 @@ void Copter::update_mount()
void Copter::update_trigger(void) void Copter::update_trigger(void)
{ {
#if CAMERA == ENABLED #if CAMERA == ENABLED
camera.trigger_pic_cleanup(); camera.update_trigger();
if (camera.check_trigger_pin()) {
gcs().send_message(MSG_CAMERA_FEEDBACK);
if (should_log(MASK_LOG_CAMERA)) {
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
}
}
#endif #endif
} }
@ -533,15 +527,9 @@ void Copter::update_GPS(void)
// set system time if necessary // set system time if necessary
set_system_time_from_GPS(); set_system_time_from_GPS();
// checks to initialise home and take location based pictures
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
#if CAMERA == ENABLED #if CAMERA == ENABLED
if (camera.update_location(current_loc, copter.ahrs) == true) { camera.update();
do_take_picture();
}
#endif #endif
}
} }
} }

View File

@ -71,7 +71,7 @@ Copter::Copter(void) :
auto_trim_counter(0), auto_trim_counter(0),
ServoRelayEvents(relay), ServoRelayEvents(relay),
#if CAMERA == ENABLED #if CAMERA == ENABLED
camera(&relay), camera(&relay, MASK_LOG_CAMERA, current_loc, gps, ahrs),
#endif #endif
#if MOUNT == ENABLED #if MOUNT == ENABLED
camera_mount(ahrs, current_loc), camera_mount(ahrs, current_loc),

View File

@ -779,8 +779,6 @@ private:
bool verify_wait_delay(); bool verify_wait_delay();
bool verify_within_distance(); bool verify_within_distance();
bool verify_yaw(); bool verify_yaw();
void do_take_picture();
void log_picture();
MAV_RESULT mavlink_compassmot(mavlink_channel_t chan); MAV_RESULT mavlink_compassmot(mavlink_channel_t chan);
void delay(uint32_t ms); void delay(uint32_t ms);
bool acro_init(bool ignore_checks); bool acro_init(bool ignore_checks);

View File

@ -435,7 +435,7 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
case MSG_CAMERA_FEEDBACK: case MSG_CAMERA_FEEDBACK:
#if CAMERA == ENABLED #if CAMERA == ENABLED
CHECK_PAYLOAD_SIZE(CAMERA_FEEDBACK); CHECK_PAYLOAD_SIZE(CAMERA_FEEDBACK);
copter.camera.send_feedback(chan, copter.gps, copter.ahrs, copter.current_loc); copter.camera.send_feedback(chan);
#endif #endif
break; break;
@ -1076,14 +1076,12 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
break; break;
case MAV_CMD_DO_DIGICAM_CONTROL: case MAV_CMD_DO_DIGICAM_CONTROL:
if (copter.camera.control(packet.param1, copter.camera.control(packet.param1,
packet.param2, packet.param2,
packet.param3, packet.param3,
packet.param4, packet.param4,
packet.param5, packet.param5,
packet.param6)) { packet.param6);
copter.log_picture();
}
result = MAV_RESULT_ACCEPTED; result = MAV_RESULT_ACCEPTED;
break; break;
@ -1705,7 +1703,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
//deprecated. Use MAV_CMD_DO_DIGICAM_CONTROL //deprecated. Use MAV_CMD_DO_DIGICAM_CONTROL
case MAVLINK_MSG_ID_DIGICAM_CONTROL: case MAVLINK_MSG_ID_DIGICAM_CONTROL:
copter.camera.control_msg(msg); copter.camera.control_msg(msg);
copter.log_picture();
break; break;
#endif // CAMERA == ENABLED #endif // CAMERA == ENABLED

View File

@ -1134,36 +1134,12 @@ void Copter::do_digicam_configure(const AP_Mission::Mission_Command& cmd)
// do_digicam_control Send Digicam Control message with the camera library // do_digicam_control Send Digicam Control message with the camera library
void Copter::do_digicam_control(const AP_Mission::Mission_Command& cmd) void Copter::do_digicam_control(const AP_Mission::Mission_Command& cmd)
{ {
if (camera.control(cmd.content.digicam_control.session, camera.control(cmd.content.digicam_control.session,
cmd.content.digicam_control.zoom_pos, cmd.content.digicam_control.zoom_pos,
cmd.content.digicam_control.zoom_step, cmd.content.digicam_control.zoom_step,
cmd.content.digicam_control.focus_lock, cmd.content.digicam_control.focus_lock,
cmd.content.digicam_control.shooting_cmd, cmd.content.digicam_control.shooting_cmd,
cmd.content.digicam_control.cmd_id)) { cmd.content.digicam_control.cmd_id);
log_picture();
}
}
// do_take_picture - take a picture with the camera library
void Copter::do_take_picture()
{
camera.trigger_pic(true);
log_picture();
}
// log_picture - log picture taken and send feedback to GCS
void Copter::log_picture()
{
if (!camera.using_feedback_pin()) {
gcs().send_message(MSG_CAMERA_FEEDBACK);
if (should_log(MASK_LOG_CAMERA)) {
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
}
} else {
if (should_log(MASK_LOG_CAMERA)) {
DataFlash.Log_Write_Trigger(ahrs, gps, current_loc);
}
}
} }
#endif #endif

View File

@ -298,7 +298,7 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
case AUXSW_CAMERA_TRIGGER: case AUXSW_CAMERA_TRIGGER:
#if CAMERA == ENABLED #if CAMERA == ENABLED
if (ch_flag == AUX_SWITCH_HIGH) { if (ch_flag == AUX_SWITCH_HIGH) {
do_take_picture(); camera.take_picture();
} }
#endif #endif
break; break;