AP_Mission: support MAV_CMD_NAV_DELAY command
This commit is contained in:
parent
28b52a6b78
commit
d771017c25
@ -585,6 +585,13 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
|
||||
cmd.p1 = packet.param1; // on/off. >0.5 means "on", hand-over control to external controller
|
||||
break;
|
||||
|
||||
case MAV_CMD_NAV_DELAY: // MAV ID: 94
|
||||
cmd.content.nav_delay.seconds = packet.param1; // delay in seconds
|
||||
cmd.content.nav_delay.hour_utc = packet.param2;// absolute time's hour (utc)
|
||||
cmd.content.nav_delay.min_utc = packet.param3;// absolute time's min (utc)
|
||||
cmd.content.nav_delay.sec_utc = packet.param4; // absolute time's second (utc)
|
||||
break;
|
||||
|
||||
case MAV_CMD_CONDITION_DELAY: // MAV ID: 112
|
||||
cmd.content.delay.seconds = packet.param1; // delay in seconds
|
||||
break;
|
||||
@ -1007,6 +1014,13 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
|
||||
packet.param1 = cmd.p1; // on/off. >0.5 means "on", hand-over control to external controller
|
||||
break;
|
||||
|
||||
case MAV_CMD_NAV_DELAY: // MAV ID: 94
|
||||
packet.param1 = cmd.content.nav_delay.seconds; // delay in seconds
|
||||
packet.param2 = cmd.content.nav_delay.hour_utc; // absolute time's day of week (utc)
|
||||
packet.param3 = cmd.content.nav_delay.min_utc; // absolute time's hour (utc)
|
||||
packet.param4 = cmd.content.nav_delay.sec_utc; // absolute time's min (utc)
|
||||
break;
|
||||
|
||||
case MAV_CMD_CONDITION_DELAY: // MAV ID: 112
|
||||
packet.param1 = cmd.content.delay.seconds; // delay in seconds
|
||||
break;
|
||||
|
@ -161,6 +161,14 @@ public:
|
||||
uint8_t target_state;
|
||||
};
|
||||
|
||||
// navigation delay command structure
|
||||
struct PACKED Navigation_Delay_Command {
|
||||
float seconds; // period of delay in seconds
|
||||
int8_t hour_utc; // absolute time's hour (utc)
|
||||
int8_t min_utc; // absolute time's min (utc)
|
||||
int8_t sec_utc; // absolute time's sec (utc)
|
||||
};
|
||||
|
||||
union PACKED Content {
|
||||
// jump structure
|
||||
Jump_Command jump;
|
||||
@ -216,6 +224,9 @@ public:
|
||||
// location
|
||||
Location location; // Waypoint location
|
||||
|
||||
// navigation delay
|
||||
Navigation_Delay_Command nav_delay;
|
||||
|
||||
// raw bytes, for reading/writing to eeprom. Note that only 10 bytes are available
|
||||
// if a 16 bit command ID is used
|
||||
uint8_t bytes[12];
|
||||
|
Loading…
Reference in New Issue
Block a user