mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: update for changed AP_Camera API
This commit is contained in:
parent
eed575886c
commit
4efb9bd785
|
@ -127,7 +127,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
|||
SCHED_TASK(gcs_send_deferred, 50, 550),
|
||||
SCHED_TASK(gcs_data_stream_send, 50, 550),
|
||||
SCHED_TASK(update_mount, 50, 75),
|
||||
SCHED_TASK(update_trigger, 8, 75),
|
||||
SCHED_TASK(update_trigger, 50, 75),
|
||||
SCHED_TASK(ten_hz_logging_loop, 10, 350),
|
||||
SCHED_TASK(fifty_hz_logging_loop, 50, 110),
|
||||
SCHED_TASK(full_rate_logging_loop,400, 100),
|
||||
|
@ -347,12 +347,11 @@ void Copter::update_trigger(void)
|
|||
{
|
||||
#if CAMERA == ENABLED
|
||||
camera.trigger_pic_cleanup();
|
||||
if(camera._camera_triggered == 0 && camera._feedback_pin != -1 && check_digital_pin(camera._feedback_pin) == 0){
|
||||
gcs_send_message(MSG_CAMERA_FEEDBACK);
|
||||
if (should_log(MASK_LOG_CAMERA)) {
|
||||
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
|
||||
}
|
||||
camera._camera_triggered = 1;
|
||||
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
|
||||
}
|
||||
|
@ -656,4 +655,4 @@ void Copter::update_altitude()
|
|||
}
|
||||
}
|
||||
|
||||
AP_HAL_MAIN_CALLBACKS(&copter);
|
||||
AP_HAL_MAIN_CALLBACKS(&copter);
|
||||
|
|
|
@ -959,7 +959,6 @@ private:
|
|||
bool optflow_position_ok();
|
||||
void update_auto_armed();
|
||||
void check_usb_mux(void);
|
||||
uint8_t check_digital_pin(uint8_t pin);
|
||||
void frsky_telemetry_send(void);
|
||||
bool should_log(uint32_t mask);
|
||||
bool current_mode_has_user_takeoff(bool must_navigate);
|
||||
|
@ -1055,4 +1054,4 @@ extern Copter copter;
|
|||
using AP_HAL::millis;
|
||||
using AP_HAL::micros;
|
||||
|
||||
#endif // _COPTER_H_
|
||||
#endif // _COPTER_H_
|
||||
|
|
|
@ -50,7 +50,6 @@ bool Copter::print_log_menu(void)
|
|||
PLOG(COMPASS);
|
||||
PLOG(CAMERA);
|
||||
PLOG(PID);
|
||||
PLOG(TRIGGER);
|
||||
#undef PLOG
|
||||
}
|
||||
|
||||
|
@ -133,7 +132,6 @@ int8_t Copter::select_logs(uint8_t argc, const Menu::arg *argv)
|
|||
TARG(COMPASS);
|
||||
TARG(CAMERA);
|
||||
TARG(PID);
|
||||
TARG(TRIGGER);
|
||||
#undef TARG
|
||||
}
|
||||
|
||||
|
@ -907,4 +905,4 @@ void Copter::Log_Write_Optflow() {}
|
|||
void Copter::start_logging() {}
|
||||
void Copter::log_init(void) {}
|
||||
|
||||
#endif // LOGGING_ENABLED
|
||||
#endif // LOGGING_ENABLED
|
||||
|
|
|
@ -895,17 +895,15 @@ void Copter::do_take_picture()
|
|||
// log_picture - log picture taken and send feedback to GCS
|
||||
void Copter::log_picture()
|
||||
{
|
||||
if (camera._feedback_pin == -1 ){
|
||||
gcs_send_message(MSG_CAMERA_FEEDBACK);
|
||||
if (should_log(MASK_LOG_CAMERA)) {
|
||||
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
|
||||
}
|
||||
}
|
||||
else {
|
||||
camera._camera_triggered = 0;
|
||||
if (should_log(MASK_LOG_TRIGGER)) {
|
||||
DataFlash.Log_Write_Trigger(ahrs, gps, current_loc);
|
||||
}
|
||||
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);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -915,4 +913,4 @@ void Copter::do_mount_control(const AP_Mission::Mission_Command& cmd)
|
|||
#if MOUNT == ENABLED
|
||||
camera_mount.set_angle_targets(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
|
|
@ -278,7 +278,6 @@ enum FlipState {
|
|||
#define MASK_LOG_MOTBATT (1UL<<17)
|
||||
#define MASK_LOG_IMU_FAST (1UL<<18)
|
||||
#define MASK_LOG_IMU_RAW (1UL<<19)
|
||||
#define MASK_LOG_TRIGGER (1UL<<20)
|
||||
#define MASK_LOG_ANY 0xFFFF
|
||||
|
||||
// DATA - event logging
|
||||
|
@ -427,4 +426,4 @@ enum FlipState {
|
|||
#define THR_BEHAVE_FEEDBACK_FROM_MID_STICK (1<<0)
|
||||
#define THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND (1<<1)
|
||||
|
||||
#endif // _DEFINES_H
|
||||
#endif // _DEFINES_H
|
||||
|
|
|
@ -432,24 +432,6 @@ void Copter::frsky_telemetry_send(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
check a digitial pin for high,low (1/0)
|
||||
*/
|
||||
uint8_t Copter::check_digital_pin(uint8_t pin)
|
||||
{
|
||||
int8_t dpin = hal.gpio->analogPinToDigitalPin(pin);
|
||||
if (dpin == -1) {
|
||||
return 0;
|
||||
}
|
||||
// ensure we are in input mode
|
||||
hal.gpio->pinMode(dpin, HAL_GPIO_INPUT);
|
||||
|
||||
// enable pullup
|
||||
hal.gpio->write(dpin, 1);
|
||||
|
||||
return hal.gpio->read(dpin);
|
||||
}
|
||||
|
||||
/*
|
||||
should we log a message type now?
|
||||
*/
|
||||
|
@ -467,4 +449,4 @@ bool Copter::should_log(uint32_t mask)
|
|||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue