Plane: add AP_Mission object to parameter list
This commit is contained in:
parent
04166c1686
commit
fdaf3fc177
@ -154,6 +154,7 @@ public:
|
|||||||
k_param_airspeed, // AP_Airspeed parameters
|
k_param_airspeed, // AP_Airspeed parameters
|
||||||
k_param_curr_amp_offset,
|
k_param_curr_amp_offset,
|
||||||
k_param_NavEKF, // Extended Kalman Filter Inertial Navigation Group
|
k_param_NavEKF, // Extended Kalman Filter Inertial Navigation Group
|
||||||
|
k_param_mission, // mission library
|
||||||
|
|
||||||
//
|
//
|
||||||
// 150: Navigation parameters
|
// 150: Navigation parameters
|
||||||
@ -242,8 +243,8 @@ public:
|
|||||||
// 220: Waypoint data
|
// 220: Waypoint data
|
||||||
//
|
//
|
||||||
k_param_waypoint_mode = 220,
|
k_param_waypoint_mode = 220,
|
||||||
k_param_command_total,
|
k_param_command_total, // unused
|
||||||
k_param_command_index,
|
k_param_command_index, // unused
|
||||||
k_param_waypoint_radius,
|
k_param_waypoint_radius,
|
||||||
k_param_loiter_radius,
|
k_param_loiter_radius,
|
||||||
k_param_fence_action,
|
k_param_fence_action,
|
||||||
@ -325,8 +326,6 @@ public:
|
|||||||
// Waypoints
|
// Waypoints
|
||||||
//
|
//
|
||||||
AP_Int8 waypoint_mode;
|
AP_Int8 waypoint_mode;
|
||||||
AP_Int8 command_total;
|
|
||||||
AP_Int8 command_index;
|
|
||||||
AP_Int16 waypoint_radius;
|
AP_Int16 waypoint_radius;
|
||||||
AP_Int16 waypoint_max_radius;
|
AP_Int16 waypoint_max_radius;
|
||||||
AP_Int16 loiter_radius;
|
AP_Int16 loiter_radius;
|
||||||
|
@ -198,20 +198,6 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
GSCALAR(alt_offset, "ALT_OFFSET", 0),
|
GSCALAR(alt_offset, "ALT_OFFSET", 0),
|
||||||
|
|
||||||
// @Param: CMD_TOTAL
|
|
||||||
// @DisplayName: Number of loaded mission items
|
|
||||||
// @Description: The number of mission mission items that has been loaded by the ground station. Do not change this manually.
|
|
||||||
// @Range: 1 255
|
|
||||||
// @User: Advanced
|
|
||||||
GSCALAR(command_total, "CMD_TOTAL", 0),
|
|
||||||
|
|
||||||
// @Param: CMD_INDEX
|
|
||||||
// @DisplayName: Current mission command index
|
|
||||||
// @Description: The index of the currently running mission item. Do not change this manually.
|
|
||||||
// @Range: 1 255
|
|
||||||
// @User: Advanced
|
|
||||||
GSCALAR(command_index, "CMD_INDEX", 0),
|
|
||||||
|
|
||||||
// @Param: WP_RADIUS
|
// @Param: WP_RADIUS
|
||||||
// @DisplayName: Waypoint Radius
|
// @DisplayName: Waypoint Radius
|
||||||
// @Description: Defines the distance from a waypoint that when crossed indicates the waypoint has been completed. To avoid the aircraft looping around the waypoint in case it misses by more than the WP_RADIUS an additional check is made to see if the aircraft has crossed a "finish line" passing through the waypoint and perpendicular to the flight path from the previous waypoint. If that finish line is crossed then the waypoint is considered complete.
|
// @Description: Defines the distance from a waypoint that when crossed indicates the waypoint has been completed. To avoid the aircraft looping around the waypoint in case it misses by more than the WP_RADIUS an additional check is made to see if the aircraft has crossed a "finish line" passing through the waypoint and perpendicular to the flight path from the previous waypoint. If that finish line is crossed then the waypoint is considered complete.
|
||||||
@ -979,6 +965,10 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
GOBJECTN(ahrs.get_NavEKF(), NavEKF, "EKF_", NavEKF),
|
GOBJECTN(ahrs.get_NavEKF(), NavEKF, "EKF_", NavEKF),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// @Group: MIS_
|
||||||
|
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
|
||||||
|
GOBJECT(mission, "MIS_", AP_Mission),
|
||||||
|
|
||||||
AP_VAREND
|
AP_VAREND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user