Copter: add attitude and pos control params

This commit is contained in:
Randy Mackay 2014-01-10 23:29:55 +09:00 committed by Andrew Tridgell
parent b34664ea07
commit 784f7385b5
2 changed files with 11 additions and 1 deletions

View File

@ -137,7 +137,9 @@ public:
// 100: Inertial Nav
//
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
//

View File

@ -1007,6 +1007,14 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Path: ../libraries/AC_WPNav/AC_WPNav.cpp
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_
// @Path: GCS_Mavlink.pde
GOBJECTN(gcs[0], gcs0, "SR0_", GCS_MAVLINK),