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

This commit is contained in:
Peter Barker 2017-07-26 12:45:55 +10:00 committed by Andrew Tridgell
parent 851f23fe9c
commit 066d501e8d
5 changed files with 16 additions and 55 deletions

View File

@ -207,13 +207,7 @@ void Rover::mount_update(void)
void Rover::update_trigger(void) void Rover::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
} }
@ -403,9 +397,7 @@ void Rover::update_GPS_10Hz(void)
ground_speed = ahrs.groundspeed(); ground_speed = ahrs.groundspeed();
#if CAMERA == ENABLED #if CAMERA == ENABLED
if (camera.update_location(current_loc, rover.ahrs) == true) { camera.update();
do_take_picture();
}
#endif #endif
} }
} }

View File

@ -456,7 +456,7 @@ bool GCS_MAVLINK_Rover::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);
rover.camera.send_feedback(chan, rover.gps, rover.ahrs, rover.current_loc); rover.camera.send_feedback(chan);
#endif #endif
break; break;
@ -838,14 +838,12 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
break; break;
case MAV_CMD_DO_DIGICAM_CONTROL: case MAV_CMD_DO_DIGICAM_CONTROL:
if (rover.camera.control(packet.param1, rover.camera.control(packet.param1,
packet.param2, packet.param2,
packet.param3, packet.param3,
packet.param4, packet.param4,
packet.param5, packet.param5,
packet.param6)) { packet.param6);
rover.log_picture();
}
result = MAV_RESULT_ACCEPTED; result = MAV_RESULT_ACCEPTED;
break; break;
@ -1366,7 +1364,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
case MAVLINK_MSG_ID_DIGICAM_CONTROL: case MAVLINK_MSG_ID_DIGICAM_CONTROL:
{ {
rover.camera.control_msg(msg); rover.camera.control_msg(msg);
rover.log_picture();
break; break;
} }
#endif // CAMERA == ENABLED #endif // CAMERA == ENABLED

View File

@ -35,7 +35,7 @@ Rover::Rover(void) :
FUNCTOR_BIND_MEMBER(&Rover::exit_mission, void)), FUNCTOR_BIND_MEMBER(&Rover::exit_mission, void)),
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

@ -508,10 +508,6 @@ private:
bool verify_wait_delay(); bool verify_wait_delay();
bool verify_within_distance(); bool verify_within_distance();
bool verify_yaw(); bool verify_yaw();
#if CAMERA == ENABLED
void do_take_picture();
void log_picture();
#endif
void update_commands(void); void update_commands(void);
void delay(uint32_t ms); void delay(uint32_t ms);
void mavlink_delay(uint32_t ms); void mavlink_delay(uint32_t ms);

View File

@ -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 // do_digicam_control Send Digicam Control message with the camera library
void Rover::do_digicam_control(const AP_Mission::Mission_Command& cmd) void Rover::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 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);
}
}
} }
#endif #endif