mirror of https://github.com/ArduPilot/ardupilot
AP_Mission: Added immediate trigger for DO_SET_CAM_TRIGG_DIST
This commit is contained in:
parent
824816ddcb
commit
d813ee27de
|
@ -941,6 +941,7 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
|
|||
|
||||
case MAV_CMD_DO_SET_CAM_TRIGG_DIST: // MAV ID: 206
|
||||
cmd.content.cam_trigg_dist.meters = packet.param1; // distance between camera shots in meters
|
||||
cmd.content.cam_trigg_dist.trigger = packet.param3; // when enabled, camera triggers once immediately
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_FENCE_ENABLE: // MAV ID: 207
|
||||
|
@ -1380,6 +1381,7 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
|
|||
|
||||
case MAV_CMD_DO_SET_CAM_TRIGG_DIST: // MAV ID: 206
|
||||
packet.param1 = cmd.content.cam_trigg_dist.meters; // distance between camera shots in meters
|
||||
packet.param3 = cmd.content.cam_trigg_dist.trigger; // when enabled, camera triggers once immediately
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_FENCE_ENABLE: // MAV ID: 207
|
||||
|
|
|
@ -137,6 +137,7 @@ public:
|
|||
// set cam trigger distance command structure
|
||||
struct PACKED Cam_Trigg_Distance {
|
||||
float meters; // distance
|
||||
uint8_t trigger; // triggers one image capture immediately
|
||||
};
|
||||
|
||||
// gripper command structure
|
||||
|
|
|
@ -102,6 +102,9 @@ bool AP_Mission::start_command_camera(const AP_Mission::Mission_Command& cmd)
|
|||
|
||||
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
||||
camera->set_trigger_distance(cmd.content.cam_trigg_dist.meters);
|
||||
if (cmd.content.cam_trigg_dist.trigger == 1) {
|
||||
camera->take_picture();
|
||||
}
|
||||
return true;
|
||||
|
||||
default:
|
||||
|
|
Loading…
Reference in New Issue