diff --git a/APMrover2/Parameters.h b/APMrover2/Parameters.h index 3bb03178c2..c3fb7eca7f 100644 --- a/APMrover2/Parameters.h +++ b/APMrover2/Parameters.h @@ -4,6 +4,7 @@ #include "RC_Channel.h" #include "AC_Sprayer/AC_Sprayer.h" +#include "AP_Gripper/AP_Gripper.h" #include "AP_Rally.h" // Global parameter class. diff --git a/APMrover2/Rover.cpp b/APMrover2/Rover.cpp index e1b7f8c998..6745f5a9c9 100644 --- a/APMrover2/Rover.cpp +++ b/APMrover2/Rover.cpp @@ -35,6 +35,8 @@ #include "version.h" #undef FORCE_VERSION_H_INCLUDE +#include "AP_Gripper/AP_Gripper.h" + const AP_HAL::HAL& hal = AP_HAL::get_HAL(); #define SCHED_TASK(func, _interval_ticks, _max_time_micros) SCHED_TASK_CLASS(Rover, &rover, func, _interval_ticks, _max_time_micros) @@ -114,6 +116,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { constexpr int8_t Rover::_failsafe_priorities[7]; Rover::Rover(void) : + AP_Vehicle(), param_loader(var_info), channel_steer(nullptr), channel_throttle(nullptr), diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 027d9d4943..73ee866688 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -31,13 +31,9 @@ #include #include // Battery monitor library #include -#include -#include -#include #include // Camera triggering #include // ArduPilot Mega Magnetometer Library #include // Compass declination library -#include // ArduPilot GPS library #include // Inertial Sensor (uncalibated IMU) Library #include #include // ArduPilot Mega Vector/Matrix math Library @@ -46,18 +42,11 @@ #include #include #include -#include // Notify library #include // Optical Flow library #include #include // Range finder library #include // RC input mapping library -#include // APM relay -#include -#include // RSSI Library #include // main loop scheduler -#include // Serial manager library -#include -#include #include // statistics library #include #include // needed for AHRS build @@ -73,7 +62,6 @@ #include // Filter library #include #include // Mode Filter from Filter library -#include #include #include #include @@ -159,14 +147,6 @@ private: // mapping between input channels RCMapper rcmap; - // board specific config - AP_BoardConfig BoardConfig; - -#if HAL_WITH_UAVCAN - // board specific config for CAN bus - AP_BoardConfig_CAN BoardConfig_CAN; -#endif - // primary control channels RC_Channel *channel_steer; RC_Channel *channel_throttle; @@ -174,14 +154,6 @@ private: AP_Logger logger; - // sensor drivers - AP_GPS gps; - AP_Baro barometer; - Compass compass; - AP_InertialSensor ins; - RangeFinder rangefinder; - AP_Button button; - // flight modes convenience array AP_Int8 *modes; const uint8_t num_modes = 6; @@ -207,9 +179,6 @@ private: OpticalFlow optflow; #endif - // RSSI - AP_RSSI rssi; - #if OSD_ENABLED == ENABLED AP_OSD osd; #endif @@ -218,8 +187,6 @@ private: SITL::SITL sitl; #endif - AP_SerialManager serial_manager; - // GCS handling GCS_Rover _gcs; // avoid using this; use gcs() GCS_Rover &gcs() { return _gcs; } @@ -227,11 +194,6 @@ private: // RC Channels: RC_Channels_Rover &rc() { return g2.rc_channels; } - // relay support - AP_Relay relay; - - AP_ServoRelayEvents ServoRelayEvents; - // The rover's current location struct Location current_loc; @@ -268,9 +230,6 @@ private: bool ekf; } failsafe; - // notification object for LEDs, buzzers etc (parameter set to false disables external leds) - AP_Notify notify; - // true if we have a position estimate from AHRS bool have_position; @@ -496,7 +455,6 @@ public: float simple_sin_yaw; }; -extern const AP_HAL::HAL& hal; extern Rover rover; using AP_HAL::millis;