mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Mission: Remove DO_SET_PARAMETER
This commit is contained in:
parent
6e546ba181
commit
831ae72908
@ -619,11 +619,6 @@ MAV_MISSION_RESULT AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item
|
||||
cmd.p1 = packet.param1; // p1=0 means use current location, p=1 means use provided location
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SET_PARAMETER: // MAV ID: 180
|
||||
cmd.p1 = packet.param1; // parameter number
|
||||
cmd.content.location.alt = packet.param2; // parameter value
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SET_RELAY: // MAV ID: 181
|
||||
cmd.content.relay.num = packet.param1; // relay number
|
||||
cmd.content.relay.state = packet.param2; // 0:off, 1:on
|
||||
@ -964,11 +959,6 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd,
|
||||
packet.param1 = cmd.p1; // p1=0 means use current location, p=1 means use provided location
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SET_PARAMETER: // MAV ID: 180
|
||||
packet.param1 = cmd.p1; // parameter number
|
||||
packet.param2 = cmd.content.location.alt; // parameter value
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SET_RELAY: // MAV ID: 181
|
||||
packet.param1 = cmd.content.relay.num; // relay number
|
||||
packet.param2 = cmd.content.relay.state; // 0:off, 1:on
|
||||
|
Loading…
Reference in New Issue
Block a user