mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
Copter: add attitude and pos control params
This commit is contained in:
parent
b34664ea07
commit
784f7385b5
@ -137,7 +137,9 @@ public:
|
|||||||
// 100: Inertial Nav
|
// 100: Inertial Nav
|
||||||
//
|
//
|
||||||
k_param_inertial_nav = 100,
|
k_param_inertial_nav = 100,
|
||||||
k_param_wp_nav = 101,
|
k_param_wp_nav,
|
||||||
|
k_param_attitude_control,
|
||||||
|
k_param_pos_control,
|
||||||
|
|
||||||
// 110: Telemetry control
|
// 110: Telemetry control
|
||||||
//
|
//
|
||||||
|
@ -1007,6 +1007,14 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Path: ../libraries/AC_WPNav/AC_WPNav.cpp
|
// @Path: ../libraries/AC_WPNav/AC_WPNav.cpp
|
||||||
GOBJECT(wp_nav, "WPNAV_", AC_WPNav),
|
GOBJECT(wp_nav, "WPNAV_", AC_WPNav),
|
||||||
|
|
||||||
|
// @Group: ATCON_
|
||||||
|
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp
|
||||||
|
GOBJECT(attitude_control, "ATTCON_", AC_AttitudeControl),
|
||||||
|
|
||||||
|
// @Group: POSCON_
|
||||||
|
// @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp
|
||||||
|
GOBJECT(pos_control, "POSCON_", AC_PosControl),
|
||||||
|
|
||||||
// @Group: SR0_
|
// @Group: SR0_
|
||||||
// @Path: GCS_Mavlink.pde
|
// @Path: GCS_Mavlink.pde
|
||||||
GOBJECTN(gcs[0], gcs0, "SR0_", GCS_MAVLINK),
|
GOBJECTN(gcs[0], gcs0, "SR0_", GCS_MAVLINK),
|
||||||
|
Loading…
Reference in New Issue
Block a user