Copter: fixed parameter doc paths
This commit is contained in:
parent
8504a8baad
commit
c0c25e0588
@ -691,9 +691,13 @@ const AP_Param::Info Copter::var_info[] = {
|
|||||||
GOBJECTPTR(circle_nav, "CIRCLE_", AC_Circle),
|
GOBJECTPTR(circle_nav, "CIRCLE_", AC_Circle),
|
||||||
|
|
||||||
// @Group: ATC_
|
// @Group: ATC_
|
||||||
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp
|
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp,,../libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp
|
||||||
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
|
GOBJECTPTR(attitude_control, "ATC_", AC_AttitudeControl_Heli),
|
||||||
|
#else
|
||||||
GOBJECTPTR(attitude_control, "ATC_", AC_AttitudeControl_Multi),
|
GOBJECTPTR(attitude_control, "ATC_", AC_AttitudeControl_Multi),
|
||||||
|
#endif
|
||||||
|
|
||||||
// @Group: POSCON_
|
// @Group: POSCON_
|
||||||
// @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp
|
// @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp
|
||||||
GOBJECTPTR(pos_control, "PSC", AC_PosControl),
|
GOBJECTPTR(pos_control, "PSC", AC_PosControl),
|
||||||
@ -779,7 +783,7 @@ const AP_Param::Info Copter::var_info[] = {
|
|||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
// @Group: H_
|
// @Group: H_
|
||||||
// @Path: ../libraries/AP_Motors/AP_MotorsHeli_Single.cpp
|
// @Path: ../libraries/AP_Motors/AP_MotorsHeli_Single.cpp,../libraries/AP_Motors/AP_MotorsHeli.cpp
|
||||||
GOBJECTPTR(motors, "H_", AP_MotorsHeli_Single),
|
GOBJECTPTR(motors, "H_", AP_MotorsHeli_Single),
|
||||||
#else
|
#else
|
||||||
// @Group: MOT_
|
// @Group: MOT_
|
||||||
|
Loading…
Reference in New Issue
Block a user