forked from Archive/PX4-Autopilot
Navigator: Leverage overlapping fields in logic to save RAM by makeing them overlap in memory as well
This commit is contained in:
parent
4160b65edb
commit
5899ce715d
|
@ -100,26 +100,34 @@ enum ORIGIN {
|
|||
*/
|
||||
#pragma pack(push, 1)
|
||||
struct mission_item_s {
|
||||
bool altitude_is_relative; /**< true if altitude is relative from start point */
|
||||
double lat; /**< latitude in degrees */
|
||||
double lon; /**< longitude in degrees */
|
||||
float altitude; /**< altitude in meters (AMSL) */
|
||||
float yaw; /**< in radians NED -PI..+PI, NAN means don't change yaw */
|
||||
float loiter_radius; /**< loiter radius in meters, 0 for a VTOL to hover */
|
||||
int8_t loiter_direction; /**< 1: positive / clockwise, -1, negative. */
|
||||
bool loiter_exit_xtrack; /**< exit xtrack location: 0 for center of loiter wp, 1 for exit location */
|
||||
enum NAV_CMD nav_cmd; /**< navigation command */
|
||||
float acceptance_radius; /**< default radius in which the mission is accepted as reached in meters */
|
||||
float time_inside; /**< time that the MAV should stay inside the radius before advancing in seconds */
|
||||
float pitch_min; /**< minimal pitch angle for fixed wing takeoff waypoints */
|
||||
bool autocontinue; /**< true if next waypoint should follow after this one */
|
||||
unsigned origin; /**< where the waypoint has been generated */
|
||||
int do_jump_mission_index; /**< index where the do jump will go to */
|
||||
unsigned do_jump_repeat_count; /**< how many times do jump needs to be done */
|
||||
unsigned do_jump_current_count; /**< count how many times the jump has been done */
|
||||
float params[7]; /**< array to store mission command values for MAV_FRAME_MISSION ***/
|
||||
int8_t frame; /**< mission frame ***/
|
||||
bool force_heading; /**< heading needs to be reached ***/
|
||||
union {
|
||||
struct {
|
||||
union {
|
||||
float time_inside; /**< time that the MAV should stay inside the radius before advancing in seconds */
|
||||
float pitch_min; /**< minimal pitch angle for fixed wing takeoff waypoints */
|
||||
};
|
||||
float acceptance_radius; /**< default radius in which the mission is accepted as reached in meters */
|
||||
float loiter_radius; /**< loiter radius in meters, 0 for a VTOL to hover */
|
||||
float yaw; /**< in radians NED -PI..+PI, NAN means don't change yaw */
|
||||
float ___lat_float; /**< padding */
|
||||
float ___lon_float; /**< padding */
|
||||
float altitude; /**< altitude in meters (AMSL) */
|
||||
};
|
||||
float params[7]; /**< array to store mission command values for MAV_FRAME_MISSION ***/
|
||||
};
|
||||
enum NAV_CMD nav_cmd; /**< navigation command */
|
||||
int16_t do_jump_mission_index; /**< index where the do jump will go to */
|
||||
uint16_t do_jump_repeat_count; /**< how many times do jump needs to be done */
|
||||
uint16_t do_jump_current_count; /**< count how many times the jump has been done */
|
||||
uint16_t origin; /**< where the waypoint has been generated */
|
||||
bool loiter_exit_xtrack; /**< exit xtrack location: 0 for center of loiter wp, 1 for exit location */
|
||||
bool force_heading; /**< heading needs to be reached ***/
|
||||
bool altitude_is_relative; /**< true if altitude is relative from start point */
|
||||
bool autocontinue; /**< true if next waypoint should follow after this one */
|
||||
int8_t frame; /**< mission frame ***/
|
||||
int8_t loiter_direction; /**< 1: positive / clockwise, -1, negative. */
|
||||
};
|
||||
#pragma pack(pop)
|
||||
#include <uORB/topics/mission.h>
|
||||
|
|
Loading…
Reference in New Issue