Browse Source

Add support for SET_CAMERA_MODE command; Not used yet.

sbg
Mohammed Kabir 8 years ago committed by Lorenz Meier
parent
commit
ad5fe5f44a
  1. 1
      msg/vehicle_command.msg
  2. 1
      src/modules/commander/commander.cpp
  3. 2
      src/modules/mavlink/mavlink_mission.cpp
  4. 1
      src/modules/navigator/mission_block.cpp
  5. 1
      src/modules/navigator/mission_feasibility_checker.cpp
  6. 1
      src/modules/navigator/navigation.h

1
msg/vehicle_command.msg

@ -60,6 +60,7 @@ uint32 VEHICLE_CMD_OVERRIDE_GOTO = 252 # Hold / continue the current action |M @@ -60,6 +60,7 @@ uint32 VEHICLE_CMD_OVERRIDE_GOTO = 252 # Hold / continue the current action |M
uint32 VEHICLE_CMD_MISSION_START = 300 # start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)|
uint32 VEHICLE_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component |1 to arm, 0 to disarm|
uint32 VEHICLE_CMD_START_RX_PAIR = 500 # Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX|
uint32 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.)
uint32 VEHICLE_CMD_DO_TRIGGER_CONTROL = 2003 # Enable or disable on-board camera triggering system
uint32 VEHICLE_CMD_DO_VTOL_TRANSITION = 3000 # Command VTOL transition
uint32 VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001 # Prepare a payload deployment in the flight plan

1
src/modules/commander/commander.cpp

@ -1227,6 +1227,7 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s @@ -1227,6 +1227,7 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
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_SET_CAMERA_MODE:
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:

2
src/modules/mavlink/mavlink_mission.cpp

@ -1036,6 +1036,7 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t * @@ -1036,6 +1036,7 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t *
case NAV_CMD_ROI:
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
case MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL:
case MAV_CMD_SET_CAMERA_MODE:
case MAV_CMD_DO_VTOL_TRANSITION:
case MAV_CMD_NAV_DELAY:
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
@ -1113,6 +1114,7 @@ MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s * @@ -1113,6 +1114,7 @@ MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s *
case NAV_CMD_ROI:
case NAV_CMD_DO_SET_CAM_TRIGG_DIST:
case NAV_CMD_DO_SET_CAM_TRIGG_INTERVAL:
case NAV_CMD_SET_CAMERA_MODE:
case NAV_CMD_DO_VTOL_TRANSITION:
break;

1
src/modules/navigator/mission_block.cpp

@ -99,6 +99,7 @@ MissionBlock::is_mission_item_reached() @@ -99,6 +99,7 @@ MissionBlock::is_mission_item_reached()
case NAV_CMD_ROI:
case NAV_CMD_DO_SET_CAM_TRIGG_DIST:
case NAV_CMD_DO_SET_CAM_TRIGG_INTERVAL:
case NAV_CMD_SET_CAMERA_MODE:
return true;
case NAV_CMD_DO_VTOL_TRANSITION:

1
src/modules/navigator/mission_feasibility_checker.cpp

@ -292,6 +292,7 @@ MissionFeasibilityChecker::checkMissionItemValidity(dm_item_t dm_current, size_t @@ -292,6 +292,7 @@ MissionFeasibilityChecker::checkMissionItemValidity(dm_item_t dm_current, size_t
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_SET_CAMERA_MODE &&
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),

1
src/modules/navigator/navigation.h

@ -80,6 +80,7 @@ enum NAV_CMD { @@ -80,6 +80,7 @@ enum NAV_CMD {
NAV_CMD_DO_MOUNT_CONTROL = 205,
NAV_CMD_DO_SET_CAM_TRIGG_INTERVAL = 214,
NAV_CMD_DO_SET_CAM_TRIGG_DIST = 206,
NAV_CMD_SET_CAMERA_MODE = 530,
NAV_CMD_IMAGE_START_CAPTURE = 2000,
NAV_CMD_IMAGE_STOP_CAPTURE = 2001,
NAV_CMD_DO_TRIGGER_CONTROL = 2003,

Loading…
Cancel
Save