mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Mission: added ALTITUDE_WAIT NAV command
used for HAB launch
This commit is contained in:
parent
c415bfe766
commit
08acde2766
@ -671,6 +671,11 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP
|
||||
cmd.content.guided_limits.alt_min = packet.param2; // min alt below which the command will be aborted. 0 for no lower alt limit
|
||||
cmd.content.guided_limits.alt_max = packet.param3; // max alt above which the command will be aborted. 0 for no upper alt limit
|
||||
cmd.content.guided_limits.horiz_max = packet.param4;// max horizontal distance the vehicle can move before the command will be aborted. 0 for no horizontal limit
|
||||
|
||||
case MAV_CMD_NAV_ALTITUDE_WAIT:
|
||||
cmd.content.altitude_wait.altitude = packet.param1;
|
||||
cmd.content.altitude_wait.descent_rate = packet.param2;
|
||||
cmd.content.altitude_wait.wiggle_time = packet.param3;
|
||||
break;
|
||||
|
||||
default:
|
||||
@ -974,6 +979,11 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd,
|
||||
packet.param2 = cmd.content.guided_limits.alt_min; // min alt below which the command will be aborted. 0 for no lower alt limit
|
||||
packet.param3 = cmd.content.guided_limits.alt_max; // max alt above which the command will be aborted. 0 for no upper alt limit
|
||||
packet.param4 = cmd.content.guided_limits.horiz_max;// max horizontal distance the vehicle can move before the command will be aborted. 0 for no horizontal limit
|
||||
|
||||
case MAV_CMD_NAV_ALTITUDE_WAIT:
|
||||
packet.param1 = cmd.content.altitude_wait.altitude;
|
||||
packet.param2 = cmd.content.altitude_wait.descent_rate;
|
||||
packet.param3 = cmd.content.altitude_wait.wiggle_time;
|
||||
break;
|
||||
|
||||
default:
|
||||
|
@ -146,6 +146,13 @@ public:
|
||||
uint8_t action; // action (0 = release, 1 = grab)
|
||||
};
|
||||
|
||||
// high altitude balloon altitude wait
|
||||
struct PACKED Altitude_Wait {
|
||||
float altitude; // meters
|
||||
float descent_rate; // m/s
|
||||
uint8_t wiggle_time; // seconds
|
||||
};
|
||||
|
||||
// nav guided command
|
||||
struct PACKED Guided_Limits_Command {
|
||||
// max time is held in p1 field
|
||||
@ -200,6 +207,9 @@ public:
|
||||
// do-guided-limits
|
||||
Guided_Limits_Command guided_limits;
|
||||
|
||||
// cam trigg distance
|
||||
Altitude_Wait altitude_wait;
|
||||
|
||||
// location
|
||||
Location location; // Waypoint location
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user