This also stops us converting the mavlink command into a mission item before try…ing to handle it. It was the last user of the method which did the conversion from command_long into a mission command, so that method is now removed. I factored the existing handler to cut out the complicated conversion process. I could have converted from command_int -> mission_cmd instead, but this seemed neater.
Critical lines in AP_Mission.cpp to do with conversion from cmd_long -> mission_item_it_t -> mission_cmd -> field values change in this PR:
```
case MAV_CMD_DO_CHANGE_SPEED: // MAV ID: 178
cmd.content.speed.speed_type = packet.param1; // 0 = airspeed, 1 = ground speed
cmd.content.speed.target_ms = packet.param2; // target speed in m/s
cmd.content.speed.throttle_pct = packet.param3; // throttle as a percentage from 1 ~ 100%
break;
```
```
Board,AP_Periph,blimp,bootloader,copter,heli,iofirmware,plane,rover,sub
Durandal,,*,*,*,*,,-64,*,*
HerePro,*,,,,,,,,
Hitec-Airspeed,*,,,,,,,,
KakuteH7-bdshot,,*,*,*,*,,-88,*,*
MatekF405,,*,*,*,*,,-48,*,*
Pixhawk1-1M-bdshot,,*,,*,*,,-88,*,*
f103-QiotekPeriph,*,,,,,,,,
f303-Universal,*,,,,,,,,
iomcu,,,,,,*,,,
revo-mini,,*,*,*,*,,-96,*,*
skyviper-v2450,,,,*,,,,,
```