|
|
|
@ -299,6 +299,7 @@ bool AP_Mission::verify_command(const Mission_Command& cmd)
@@ -299,6 +299,7 @@ bool AP_Mission::verify_command(const Mission_Command& cmd)
|
|
|
|
|
case MAV_CMD_DO_DIGICAM_CONTROL: |
|
|
|
|
case MAV_CMD_DO_SET_CAM_TRIGG_DIST: |
|
|
|
|
case MAV_CMD_DO_PARACHUTE: |
|
|
|
|
case MAV_CMD_DO_SEND_SCRIPT_MESSAGE: |
|
|
|
|
case MAV_CMD_DO_SPRAYER: |
|
|
|
|
case MAV_CMD_DO_AUX_FUNCTION: |
|
|
|
|
case MAV_CMD_DO_SET_RESUME_REPEAT_DIST: |
|
|
|
@ -333,6 +334,8 @@ bool AP_Mission::start_command(const Mission_Command& cmd)
@@ -333,6 +334,8 @@ bool AP_Mission::start_command(const Mission_Command& cmd)
|
|
|
|
|
return start_command_camera(cmd); |
|
|
|
|
case MAV_CMD_DO_PARACHUTE: |
|
|
|
|
return start_command_parachute(cmd); |
|
|
|
|
case MAV_CMD_DO_SEND_SCRIPT_MESSAGE: |
|
|
|
|
return start_command_do_scripting(cmd); |
|
|
|
|
case MAV_CMD_DO_SPRAYER: |
|
|
|
|
return start_command_do_sprayer(cmd); |
|
|
|
|
case MAV_CMD_DO_SET_RESUME_REPEAT_DIST: |
|
|
|
@ -1110,6 +1113,13 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
@@ -1110,6 +1113,13 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
|
|
|
|
|
cmd.p1 = packet.param1; // action 0=disable, 1=enable
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MAV_CMD_DO_SEND_SCRIPT_MESSAGE: |
|
|
|
|
cmd.p1 = packet.param1; |
|
|
|
|
cmd.content.scripting.p1 = packet.param2; |
|
|
|
|
cmd.content.scripting.p2 = packet.param3; |
|
|
|
|
cmd.content.scripting.p3 = packet.param4; |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
default: |
|
|
|
|
// unrecognised command
|
|
|
|
|
return MAV_MISSION_UNSUPPORTED; |
|
|
|
@ -1559,6 +1569,13 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
@@ -1559,6 +1569,13 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
|
|
|
|
|
packet.param1 = cmd.p1; // Resume repeat distance (m)
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MAV_CMD_DO_SEND_SCRIPT_MESSAGE: |
|
|
|
|
packet.param1 = cmd.p1; |
|
|
|
|
packet.param2 = cmd.content.scripting.p1; |
|
|
|
|
packet.param3 = cmd.content.scripting.p2; |
|
|
|
|
packet.param4 = cmd.content.scripting.p3; |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
default: |
|
|
|
|
// unrecognised command
|
|
|
|
|
return false; |
|
|
|
@ -2266,6 +2283,8 @@ const char *AP_Mission::Mission_Command::type() const
@@ -2266,6 +2283,8 @@ const char *AP_Mission::Mission_Command::type() const
|
|
|
|
|
return "MountControl"; |
|
|
|
|
case MAV_CMD_DO_WINCH: |
|
|
|
|
return "Winch"; |
|
|
|
|
case MAV_CMD_DO_SEND_SCRIPT_MESSAGE: |
|
|
|
|
return "Scripting"; |
|
|
|
|
|
|
|
|
|
default: |
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL |
|
|
|
|