mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-20 11:23:06 +08:00
camera_trigger : completely refactor state handling
This commit is contained in:
committed by
Lorenz Meier
parent
7af7c86384
commit
2e92a3946d
@@ -1,4 +1,3 @@
|
||||
uint64 timestamp_utc # UTC timestamp
|
||||
|
||||
uint32 seq # Image sequence number
|
||||
|
||||
uint32 ORB_QUEUE_LENGTH = 3
|
||||
|
||||
|
||||
@@ -42,10 +42,11 @@ uint32 VEHICLE_CMD_DO_SET_ROI = 201 # Sets the region of interest (ROI) for a
|
||||
uint32 VEHICLE_CMD_DO_DIGICAM_CONTROL=203
|
||||
uint32 VEHICLE_CMD_DO_MOUNT_CONFIGURE=204 # Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty|
|
||||
uint32 VEHICLE_CMD_DO_MOUNT_CONTROL=205 # Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value|
|
||||
uint32 VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST=206 # Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty|
|
||||
uint32 VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST=206 # Mission command to set TRIG_DIST for this flight |Camera trigger distance (meters)| Shutter integration time (ms)| Empty| Empty| Empty| Empty| Empty|
|
||||
uint32 VEHICLE_CMD_DO_FENCE_ENABLE=207 # Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty|
|
||||
uint32 VEHICLE_CMD_DO_PARACHUTE=208 # Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty|
|
||||
uint32 VEHICLE_CMD_DO_INVERTED_FLIGHT=210 # Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty|
|
||||
uint32 VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL=214 # Mission command to set TRIG_INTERVAL for this flight |Camera trigger distance (meters)| Shutter integration time (ms)| Empty| Empty| Empty| Empty| Empty|
|
||||
uint32 VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT=220 # Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty|
|
||||
uint32 VEHICLE_CMD_DO_GUIDED_MASTER=221 # set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty|
|
||||
uint32 VEHICLE_CMD_DO_GUIDED_LIMITS=222 # set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty|
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -98,10 +98,10 @@ PARAM_DEFINE_FLOAT(TRIG_ACT_TIME, 40.0f);
|
||||
* Camera trigger mode
|
||||
*
|
||||
* @value 0 Disable
|
||||
* @value 1 On individual commands
|
||||
* @value 1 Time based, on command
|
||||
* @value 2 Time based, always on
|
||||
* @value 3 Distance based, always on
|
||||
* @value 4 Distance, mission controlled
|
||||
* @value 4 Distance based, on command (Survey mode)
|
||||
* @min 0
|
||||
* @max 4
|
||||
* @reboot_required true
|
||||
@@ -136,3 +136,16 @@ PARAM_DEFINE_INT32(TRIG_PINS, 56);
|
||||
* @group Camera trigger
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(TRIG_DISTANCE, 25.0f);
|
||||
|
||||
/**
|
||||
* Camera feedback mode
|
||||
*
|
||||
* Sets the camera feedback mode. This parameter will be moved once we
|
||||
* support better camera feedback.
|
||||
*
|
||||
* @value 0 No camera feedback available
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @group Camera Control
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAM_FEEDBACK, 0);
|
||||
|
||||
@@ -1226,6 +1226,7 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
|
||||
case vehicle_command_s::VEHICLE_CMD_DO_TRIGGER_CONTROL:
|
||||
case vehicle_command_s::VEHICLE_CMD_DO_DIGICAM_CONTROL:
|
||||
case vehicle_command_s::VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST:
|
||||
case vehicle_command_s::VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL:
|
||||
case vehicle_command_s::VEHICLE_CMD_DO_CHANGE_SPEED:
|
||||
case vehicle_command_s::VEHICLE_CMD_DO_LAND_START:
|
||||
case vehicle_command_s::VEHICLE_CMD_DO_GO_AROUND:
|
||||
|
||||
@@ -1024,6 +1024,7 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t *
|
||||
case MAV_CMD_DO_CHANGE_SPEED:
|
||||
case MAV_CMD_DO_SET_SERVO:
|
||||
case MAV_CMD_DO_LAND_START:
|
||||
case MAV_CMD_DO_TRIGGER_CONTROL:
|
||||
case MAV_CMD_DO_DIGICAM_CONTROL:
|
||||
case MAV_CMD_DO_MOUNT_CONFIGURE:
|
||||
case MAV_CMD_DO_MOUNT_CONTROL:
|
||||
@@ -1034,6 +1035,7 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t *
|
||||
case NAV_CMD_DO_SET_ROI:
|
||||
case NAV_CMD_ROI:
|
||||
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
||||
case MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL:
|
||||
case MAV_CMD_DO_VTOL_TRANSITION:
|
||||
case MAV_CMD_NAV_DELAY:
|
||||
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
|
||||
@@ -1099,6 +1101,7 @@ MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s *
|
||||
case NAV_CMD_DO_CHANGE_SPEED:
|
||||
case NAV_CMD_DO_SET_SERVO:
|
||||
case NAV_CMD_DO_LAND_START:
|
||||
case NAV_CMD_DO_TRIGGER_CONTROL:
|
||||
case NAV_CMD_DO_DIGICAM_CONTROL:
|
||||
case NAV_CMD_IMAGE_START_CAPTURE:
|
||||
case NAV_CMD_IMAGE_STOP_CAPTURE:
|
||||
@@ -1109,6 +1112,7 @@ MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s *
|
||||
case NAV_CMD_DO_SET_ROI:
|
||||
case NAV_CMD_ROI:
|
||||
case NAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
||||
case NAV_CMD_DO_SET_CAM_TRIGG_INTERVAL:
|
||||
case NAV_CMD_DO_VTOL_TRANSITION:
|
||||
break;
|
||||
|
||||
|
||||
@@ -73,6 +73,7 @@ bool
|
||||
MissionBlock::is_mission_item_reached()
|
||||
{
|
||||
/* handle non-navigation or indefinite waypoints */
|
||||
|
||||
switch (_mission_item.nav_cmd) {
|
||||
case NAV_CMD_DO_SET_SERVO:
|
||||
return true;
|
||||
@@ -86,6 +87,7 @@ MissionBlock::is_mission_item_reached()
|
||||
return false;
|
||||
|
||||
case NAV_CMD_DO_LAND_START:
|
||||
case NAV_CMD_DO_TRIGGER_CONTROL:
|
||||
case NAV_CMD_DO_DIGICAM_CONTROL:
|
||||
case NAV_CMD_IMAGE_START_CAPTURE:
|
||||
case NAV_CMD_IMAGE_STOP_CAPTURE:
|
||||
@@ -96,6 +98,7 @@ MissionBlock::is_mission_item_reached()
|
||||
case NAV_CMD_DO_SET_ROI:
|
||||
case NAV_CMD_ROI:
|
||||
case NAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
||||
case NAV_CMD_DO_SET_CAM_TRIGG_INTERVAL:
|
||||
return true;
|
||||
|
||||
case NAV_CMD_DO_VTOL_TRANSITION:
|
||||
@@ -445,6 +448,7 @@ MissionBlock::mission_item_to_vehicle_command(const struct mission_item_s *item,
|
||||
void
|
||||
MissionBlock::issue_command(const struct mission_item_s *item)
|
||||
{
|
||||
|
||||
if (item_contains_position(item)) {
|
||||
return;
|
||||
}
|
||||
|
||||
@@ -280,6 +280,7 @@ MissionFeasibilityChecker::checkMissionItemValidity(dm_item_t dm_current, size_t
|
||||
missionitem.nav_cmd != NAV_CMD_DO_CHANGE_SPEED &&
|
||||
missionitem.nav_cmd != NAV_CMD_DO_SET_SERVO &&
|
||||
missionitem.nav_cmd != NAV_CMD_DO_LAND_START &&
|
||||
missionitem.nav_cmd != NAV_CMD_DO_TRIGGER_CONTROL &&
|
||||
missionitem.nav_cmd != NAV_CMD_DO_DIGICAM_CONTROL &&
|
||||
missionitem.nav_cmd != NAV_CMD_IMAGE_START_CAPTURE &&
|
||||
missionitem.nav_cmd != NAV_CMD_IMAGE_STOP_CAPTURE &&
|
||||
@@ -290,6 +291,7 @@ MissionFeasibilityChecker::checkMissionItemValidity(dm_item_t dm_current, size_t
|
||||
missionitem.nav_cmd != NAV_CMD_DO_SET_ROI &&
|
||||
missionitem.nav_cmd != NAV_CMD_ROI &&
|
||||
missionitem.nav_cmd != NAV_CMD_DO_SET_CAM_TRIGG_DIST &&
|
||||
missionitem.nav_cmd != NAV_CMD_DO_SET_CAM_TRIGG_INTERVAL &&
|
||||
missionitem.nav_cmd != NAV_CMD_DO_VTOL_TRANSITION) {
|
||||
|
||||
mavlink_log_critical(_navigator->get_mavlink_log_pub(), "Mission rejected: item %i: unsupported cmd: %d", (int)(i + 1),
|
||||
|
||||
@@ -78,9 +78,11 @@ enum NAV_CMD {
|
||||
NAV_CMD_DO_DIGICAM_CONTROL = 203,
|
||||
NAV_CMD_DO_MOUNT_CONFIGURE = 204,
|
||||
NAV_CMD_DO_MOUNT_CONTROL = 205,
|
||||
NAV_CMD_DO_SET_CAM_TRIGG_INTERVAL = 214,
|
||||
NAV_CMD_DO_SET_CAM_TRIGG_DIST = 206,
|
||||
NAV_CMD_IMAGE_START_CAPTURE = 2000,
|
||||
NAV_CMD_IMAGE_STOP_CAPTURE = 2001,
|
||||
NAV_CMD_DO_TRIGGER_CONTROL = 2003,
|
||||
NAV_CMD_VIDEO_START_CAPTURE = 2500,
|
||||
NAV_CMD_VIDEO_STOP_CAPTURE = 2501,
|
||||
NAV_CMD_DO_VTOL_TRANSITION = 3000,
|
||||
|
||||
Reference in New Issue
Block a user