mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Mission: add and use AP_CAMERA_ENABLED
This commit is contained in:
parent
a18c87a120
commit
59b82507ff
@ -5,6 +5,7 @@
|
||||
#include <AP_Terrain/AP_Terrain.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_Camera/AP_Camera.h>
|
||||
|
||||
const AP_Param::GroupInfo AP_Mission::var_info[] = {
|
||||
|
||||
@ -358,8 +359,10 @@ bool AP_Mission::start_command(const Mission_Command& cmd)
|
||||
case MAV_CMD_DO_CONTROL_VIDEO:
|
||||
case MAV_CMD_DO_DIGICAM_CONFIGURE:
|
||||
case MAV_CMD_DO_DIGICAM_CONTROL:
|
||||
#if AP_CAMERA_ENABLED
|
||||
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
||||
return start_command_camera(cmd);
|
||||
#endif
|
||||
case MAV_CMD_DO_PARACHUTE:
|
||||
return start_command_parachute(cmd);
|
||||
case MAV_CMD_DO_SEND_SCRIPT_MESSAGE:
|
||||
|
@ -89,6 +89,7 @@ bool AP_Mission::start_command_do_servorelayevents(const AP_Mission::Mission_Com
|
||||
}
|
||||
}
|
||||
|
||||
#if AP_CAMERA_ENABLED
|
||||
bool AP_Mission::start_command_camera(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
AP_Camera *camera = AP::camera();
|
||||
@ -133,6 +134,7 @@ bool AP_Mission::start_command_camera(const AP_Mission::Mission_Command& cmd)
|
||||
return false;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
bool AP_Mission::start_command_parachute(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user