mirror of https://github.com/ArduPilot/ardupilot
Rover: include wheel-rate-control
This commit is contained in:
parent
85ac24d96e
commit
db611e074c
|
@ -575,6 +575,10 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
// @Path: ../libraries/AC_Sprayer/AC_Sprayer.cpp
|
||||
AP_SUBGROUPINFO(sprayer, "SPRAY_", 26, ParametersG2, AC_Sprayer),
|
||||
|
||||
// @Group: WRC
|
||||
// @Path: ../libraries/AP_WheelEncoder/AP_WheelRateControl.cpp
|
||||
AP_SUBGROUPINFO(wheel_rate_control, "WRC", 27, ParametersG2, AP_WheelRateControl),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -599,6 +603,7 @@ ParametersG2::ParametersG2(void)
|
|||
#endif
|
||||
beacon(rover.serial_manager),
|
||||
motors(rover.ServoRelayEvents),
|
||||
wheel_rate_control(wheel_encoder),
|
||||
attitude_control(rover.ahrs),
|
||||
smart_rtl(),
|
||||
fence(rover.ahrs),
|
||||
|
|
|
@ -312,6 +312,7 @@ public:
|
|||
|
||||
// wheel encoders
|
||||
AP_WheelEncoder wheel_encoder;
|
||||
AP_WheelRateControl wheel_rate_control;
|
||||
|
||||
// steering and throttle controller
|
||||
AR_AttitudeControl attitude_control;
|
||||
|
|
|
@ -65,6 +65,7 @@
|
|||
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
|
||||
#include <AP_VisualOdom/AP_VisualOdom.h>
|
||||
#include <AP_WheelEncoder/AP_WheelEncoder.h>
|
||||
#include <AP_WheelEncoder/AP_WheelRateControl.h>
|
||||
#include <APM_Control/AR_AttitudeControl.h>
|
||||
#include <AP_SmartRTL/AP_SmartRTL.h>
|
||||
#include <DataFlash/DataFlash.h>
|
||||
|
@ -565,6 +566,7 @@ public:
|
|||
|
||||
// frame type
|
||||
uint8_t get_frame_type() { return g2.frame_type.get(); }
|
||||
AP_WheelRateControl& get_wheel_rate_control() { return g2.wheel_rate_control; }
|
||||
};
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
|
Loading…
Reference in New Issue