// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include "Plane.h" const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Param: ENABLE // @DisplayName: Enable QuadPlane // @Description: This enables QuadPlane functionality, assuming quad motors on outputs 5 to 8 // @Values: 0:Disable,1:Enable // @User: Standard AP_GROUPINFO_FLAGS("ENABLE", 1, QuadPlane, enable, 0, AP_PARAM_FLAG_ENABLE), // @Group: M_ // @Path: ../libraries/AP_Motors/AP_MotorsMulticopter.cpp AP_SUBGROUPPTR(motors, "M_", 2, QuadPlane, AP_MotorsQuad), // @Param: RT_RLL_P // @DisplayName: Roll axis rate controller P gain // @Description: Roll axis rate controller P gain. Converts the difference between desired roll rate and actual roll rate into a motor speed output // @Range: 0.08 0.30 // @Increment: 0.005 // @User: Standard // @Param: RT_RLL_I // @DisplayName: Roll axis rate controller I gain // @Description: Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate // @Range: 0.01 0.5 // @Increment: 0.01 // @User: Standard
You should have received a copy of the GNU General Public License along with this program. If not, see <http://www.gnu.org/licenses/>. */ #include <AP_HAL/AP_HAL.h> #include <AP_Common/AP_Common.h> #include "AP_BoardConfig.h" #if HAL_WITH_UAVCAN #include "AP_BoardConfig_CAN.h" #include <AP_UAVCAN/AP_UAVCAN.h> // table of user settable CAN bus parameters const AP_Param::GroupInfo AP_BoardConfig_CAN::CAN_driver_var_info::var_info[] = { // @Param: PROTOCOL // @DisplayName: Enable use of specific protocol over virtual driver // @Description: Enabling this option starts selected protocol that will use this virtual driver // @Values: 0:Disabled,1:UAVCAN // @User: Advanced // @RebootRequired: True AP_GROUPINFO("PROTOCOL", 1, AP_BoardConfig_CAN::CAN_driver_var_info, _protocol, UAVCAN_PROTOCOL_ENABLE), // @Group: UC_ // @Path: ../AP_UAVCAN/AP_UAVCAN.cpp AP_SUBGROUPPTR(_uavcan, "UC_", 2, AP_BoardConfig_CAN::CAN_driver_var_info, AP_UAVCAN), AP_GROUPEND }; #endif