diff --git a/APMrover2/APMrover2.cpp b/APMrover2/APMrover2.cpp index df2c8365fb..32e4a05d93 100644 --- a/APMrover2/APMrover2.cpp +++ b/APMrover2/APMrover2.cpp @@ -207,13 +207,7 @@ void Rover::mount_update(void) void Rover::update_trigger(void) { #if CAMERA == ENABLED - camera.trigger_pic_cleanup(); - 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); - } - } + camera.update_trigger(); #endif } @@ -403,9 +397,7 @@ void Rover::update_GPS_10Hz(void) ground_speed = ahrs.groundspeed(); #if CAMERA == ENABLED - if (camera.update_location(current_loc, rover.ahrs) == true) { - do_take_picture(); - } + camera.update(); #endif } } diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index d0dd65fbba..61a0a8f3fb 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -456,7 +456,7 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id) case MSG_CAMERA_FEEDBACK: #if CAMERA == ENABLED CHECK_PAYLOAD_SIZE(CAMERA_FEEDBACK); - rover.camera.send_feedback(chan, rover.gps, rover.ahrs, rover.current_loc); + rover.camera.send_feedback(chan); #endif break; @@ -838,14 +838,12 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg) break; case MAV_CMD_DO_DIGICAM_CONTROL: - if (rover.camera.control(packet.param1, - packet.param2, - packet.param3, - packet.param4, - packet.param5, - packet.param6)) { - rover.log_picture(); - } + rover.camera.control(packet.param1, + packet.param2, + packet.param3, + packet.param4, + packet.param5, + packet.param6); result = MAV_RESULT_ACCEPTED; break; @@ -1366,7 +1364,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg) case MAVLINK_MSG_ID_DIGICAM_CONTROL: { rover.camera.control_msg(msg); - rover.log_picture(); break; } #endif // CAMERA == ENABLED diff --git a/APMrover2/Rover.cpp b/APMrover2/Rover.cpp index c418a8a65e..dde59369fb 100644 --- a/APMrover2/Rover.cpp +++ b/APMrover2/Rover.cpp @@ -35,7 +35,7 @@ Rover::Rover(void) : FUNCTOR_BIND_MEMBER(&Rover::exit_mission, void)), ServoRelayEvents(relay), #if CAMERA == ENABLED - camera(&relay), + camera(&relay, MASK_LOG_CAMERA, current_loc, gps, ahrs), #endif #if MOUNT == ENABLED camera_mount(ahrs, current_loc), diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 1e322af1e5..c640affc55 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -508,10 +508,6 @@ private: bool verify_wait_delay(); bool verify_within_distance(); bool verify_yaw(); -#if CAMERA == ENABLED - void do_take_picture(); - void log_picture(); -#endif void update_commands(void); void delay(uint32_t ms); void mavlink_delay(uint32_t ms); diff --git a/APMrover2/commands_logic.cpp b/APMrover2/commands_logic.cpp index f6c72079b1..870a907a45 100644 --- a/APMrover2/commands_logic.cpp +++ b/APMrover2/commands_logic.cpp @@ -551,36 +551,12 @@ void Rover::do_digicam_configure(const AP_Mission::Mission_Command& cmd) // do_digicam_control Send Digicam Control message with the camera library void Rover::do_digicam_control(const AP_Mission::Mission_Command& cmd) { - if (camera.control(cmd.content.digicam_control.session, - cmd.content.digicam_control.zoom_pos, - cmd.content.digicam_control.zoom_step, - cmd.content.digicam_control.focus_lock, - cmd.content.digicam_control.shooting_cmd, - cmd.content.digicam_control.cmd_id)) { - log_picture(); - } -} - -// do_take_picture - take a picture with the camera library -void Rover::do_take_picture() -{ - camera.trigger_pic(true); - log_picture(); -} - -// log_picture - log picture taken and send feedback to GCS -void Rover::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); - } - } + camera.control(cmd.content.digicam_control.session, + cmd.content.digicam_control.zoom_pos, + cmd.content.digicam_control.zoom_step, + cmd.content.digicam_control.focus_lock, + cmd.content.digicam_control.shooting_cmd, + cmd.content.digicam_control.cmd_id); } #endif