Rover: correct compilation when camera disabled
This commit is contained in:
parent
990d5fd0e5
commit
61430a51b3
@ -464,8 +464,10 @@ private:
|
||||
bool verify_RTL();
|
||||
bool verify_wait_delay();
|
||||
bool verify_within_distance();
|
||||
#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);
|
||||
@ -532,8 +534,10 @@ private:
|
||||
void do_within_distance(const AP_Mission::Mission_Command& cmd);
|
||||
void do_change_speed(const AP_Mission::Mission_Command& cmd);
|
||||
void do_set_home(const AP_Mission::Mission_Command& cmd);
|
||||
#if CAMERA == ENABLED
|
||||
void do_digicam_configure(const AP_Mission::Mission_Command& cmd);
|
||||
void do_digicam_control(const AP_Mission::Mission_Command& cmd);
|
||||
#endif
|
||||
void do_set_reverse(const AP_Mission::Mission_Command& cmd);
|
||||
void init_capabilities(void);
|
||||
void rudder_arm_disarm_check();
|
||||
|
@ -455,10 +455,11 @@ void Rover::do_set_home(const AP_Mission::Mission_Command& cmd)
|
||||
}
|
||||
}
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
|
||||
// do_digicam_configure Send Digicam Configure message with the camera library
|
||||
void Rover::do_digicam_configure(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
#if CAMERA == ENABLED
|
||||
camera.configure(cmd.content.digicam_configure.shooting_mode,
|
||||
cmd.content.digicam_configure.shutter_speed,
|
||||
cmd.content.digicam_configure.aperture,
|
||||
@ -466,13 +467,11 @@ void Rover::do_digicam_configure(const AP_Mission::Mission_Command& cmd)
|
||||
cmd.content.digicam_configure.exposure_type,
|
||||
cmd.content.digicam_configure.cmd_id,
|
||||
cmd.content.digicam_configure.engine_cutoff_time);
|
||||
#endif
|
||||
}
|
||||
|
||||
// do_digicam_control Send Digicam Control message with the camera library
|
||||
void Rover::do_digicam_control(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
#if CAMERA == ENABLED
|
||||
if (camera.control(cmd.content.digicam_control.session,
|
||||
cmd.content.digicam_control.zoom_pos,
|
||||
cmd.content.digicam_control.zoom_step,
|
||||
@ -481,16 +480,13 @@ void Rover::do_digicam_control(const AP_Mission::Mission_Command& cmd)
|
||||
cmd.content.digicam_control.cmd_id)) {
|
||||
log_picture();
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// do_take_picture - take a picture with the camera library
|
||||
void Rover::do_take_picture()
|
||||
{
|
||||
#if CAMERA == ENABLED
|
||||
camera.trigger_pic(true);
|
||||
log_picture();
|
||||
#endif
|
||||
}
|
||||
|
||||
// log_picture - log picture taken and send feedback to GCS
|
||||
@ -508,6 +504,8 @@ void Rover::log_picture()
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
void Rover::do_set_reverse(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
if (cmd.p1 == 1) {
|
||||
|
Loading…
Reference in New Issue
Block a user