mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Rover: move many members up to base class
This commit is contained in:
parent
347c247ad0
commit
3bf9a45ed1
@ -4,6 +4,7 @@
|
|||||||
|
|
||||||
#include "RC_Channel.h"
|
#include "RC_Channel.h"
|
||||||
#include "AC_Sprayer/AC_Sprayer.h"
|
#include "AC_Sprayer/AC_Sprayer.h"
|
||||||
|
#include "AP_Gripper/AP_Gripper.h"
|
||||||
#include "AP_Rally.h"
|
#include "AP_Rally.h"
|
||||||
|
|
||||||
// Global parameter class.
|
// Global parameter class.
|
||||||
|
@ -35,6 +35,8 @@
|
|||||||
#include "version.h"
|
#include "version.h"
|
||||||
#undef FORCE_VERSION_H_INCLUDE
|
#undef FORCE_VERSION_H_INCLUDE
|
||||||
|
|
||||||
|
#include "AP_Gripper/AP_Gripper.h"
|
||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
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)
|
#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];
|
constexpr int8_t Rover::_failsafe_priorities[7];
|
||||||
|
|
||||||
Rover::Rover(void) :
|
Rover::Rover(void) :
|
||||||
|
AP_Vehicle(),
|
||||||
param_loader(var_info),
|
param_loader(var_info),
|
||||||
channel_steer(nullptr),
|
channel_steer(nullptr),
|
||||||
channel_throttle(nullptr),
|
channel_throttle(nullptr),
|
||||||
|
@ -31,13 +31,9 @@
|
|||||||
#include <AP_Baro/AP_Baro.h>
|
#include <AP_Baro/AP_Baro.h>
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
|
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
|
||||||
#include <AP_Beacon/AP_Beacon.h>
|
#include <AP_Beacon/AP_Beacon.h>
|
||||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
|
||||||
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
|
|
||||||
#include <AP_Button/AP_Button.h>
|
|
||||||
#include <AP_Camera/AP_Camera.h> // Camera triggering
|
#include <AP_Camera/AP_Camera.h> // Camera triggering
|
||||||
#include <AP_Compass/AP_Compass.h> // ArduPilot Mega Magnetometer Library
|
#include <AP_Compass/AP_Compass.h> // ArduPilot Mega Magnetometer Library
|
||||||
#include <AP_Declination/AP_Declination.h> // Compass declination library
|
#include <AP_Declination/AP_Declination.h> // Compass declination library
|
||||||
#include <AP_GPS/AP_GPS.h> // ArduPilot GPS library
|
|
||||||
#include <AP_InertialSensor/AP_InertialSensor.h> // Inertial Sensor (uncalibated IMU) Library
|
#include <AP_InertialSensor/AP_InertialSensor.h> // Inertial Sensor (uncalibated IMU) Library
|
||||||
#include <AP_L1_Control/AP_L1_Control.h>
|
#include <AP_L1_Control/AP_L1_Control.h>
|
||||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
@ -46,18 +42,11 @@
|
|||||||
#include <AP_NavEKF2/AP_NavEKF2.h>
|
#include <AP_NavEKF2/AP_NavEKF2.h>
|
||||||
#include <AP_NavEKF3/AP_NavEKF3.h>
|
#include <AP_NavEKF3/AP_NavEKF3.h>
|
||||||
#include <AP_Navigation/AP_Navigation.h>
|
#include <AP_Navigation/AP_Navigation.h>
|
||||||
#include <AP_Notify/AP_Notify.h> // Notify library
|
|
||||||
#include <AP_OpticalFlow/AP_OpticalFlow.h> // Optical Flow library
|
#include <AP_OpticalFlow/AP_OpticalFlow.h> // Optical Flow library
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <AP_RangeFinder/AP_RangeFinder.h> // Range finder library
|
#include <AP_RangeFinder/AP_RangeFinder.h> // Range finder library
|
||||||
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
|
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
|
||||||
#include <AP_Relay/AP_Relay.h> // APM relay
|
|
||||||
#include <AP_RPM/AP_RPM.h>
|
|
||||||
#include <AP_RSSI/AP_RSSI.h> // RSSI Library
|
|
||||||
#include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler
|
#include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler
|
||||||
#include <AP_SerialManager/AP_SerialManager.h> // Serial manager library
|
|
||||||
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
|
|
||||||
#include <AP_Gripper/AP_Gripper.h>
|
|
||||||
#include <AP_Stats/AP_Stats.h> // statistics library
|
#include <AP_Stats/AP_Stats.h> // statistics library
|
||||||
#include <AP_Terrain/AP_Terrain.h>
|
#include <AP_Terrain/AP_Terrain.h>
|
||||||
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
|
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
|
||||||
@ -73,7 +62,6 @@
|
|||||||
#include <Filter/Filter.h> // Filter library
|
#include <Filter/Filter.h> // Filter library
|
||||||
#include <Filter/LowPassFilter.h>
|
#include <Filter/LowPassFilter.h>
|
||||||
#include <Filter/ModeFilter.h> // Mode Filter from Filter library
|
#include <Filter/ModeFilter.h> // Mode Filter from Filter library
|
||||||
#include <StorageManager/StorageManager.h>
|
|
||||||
#include <AC_Fence/AC_Fence.h>
|
#include <AC_Fence/AC_Fence.h>
|
||||||
#include <AP_Proximity/AP_Proximity.h>
|
#include <AP_Proximity/AP_Proximity.h>
|
||||||
#include <AC_Avoidance/AC_Avoid.h>
|
#include <AC_Avoidance/AC_Avoid.h>
|
||||||
@ -159,14 +147,6 @@ private:
|
|||||||
// mapping between input channels
|
// mapping between input channels
|
||||||
RCMapper rcmap;
|
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
|
// primary control channels
|
||||||
RC_Channel *channel_steer;
|
RC_Channel *channel_steer;
|
||||||
RC_Channel *channel_throttle;
|
RC_Channel *channel_throttle;
|
||||||
@ -174,14 +154,6 @@ private:
|
|||||||
|
|
||||||
AP_Logger logger;
|
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
|
// flight modes convenience array
|
||||||
AP_Int8 *modes;
|
AP_Int8 *modes;
|
||||||
const uint8_t num_modes = 6;
|
const uint8_t num_modes = 6;
|
||||||
@ -207,9 +179,6 @@ private:
|
|||||||
OpticalFlow optflow;
|
OpticalFlow optflow;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// RSSI
|
|
||||||
AP_RSSI rssi;
|
|
||||||
|
|
||||||
#if OSD_ENABLED == ENABLED
|
#if OSD_ENABLED == ENABLED
|
||||||
AP_OSD osd;
|
AP_OSD osd;
|
||||||
#endif
|
#endif
|
||||||
@ -218,8 +187,6 @@ private:
|
|||||||
SITL::SITL sitl;
|
SITL::SITL sitl;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
AP_SerialManager serial_manager;
|
|
||||||
|
|
||||||
// GCS handling
|
// GCS handling
|
||||||
GCS_Rover _gcs; // avoid using this; use gcs()
|
GCS_Rover _gcs; // avoid using this; use gcs()
|
||||||
GCS_Rover &gcs() { return _gcs; }
|
GCS_Rover &gcs() { return _gcs; }
|
||||||
@ -227,11 +194,6 @@ private:
|
|||||||
// RC Channels:
|
// RC Channels:
|
||||||
RC_Channels_Rover &rc() { return g2.rc_channels; }
|
RC_Channels_Rover &rc() { return g2.rc_channels; }
|
||||||
|
|
||||||
// relay support
|
|
||||||
AP_Relay relay;
|
|
||||||
|
|
||||||
AP_ServoRelayEvents ServoRelayEvents;
|
|
||||||
|
|
||||||
// The rover's current location
|
// The rover's current location
|
||||||
struct Location current_loc;
|
struct Location current_loc;
|
||||||
|
|
||||||
@ -268,9 +230,6 @@ private:
|
|||||||
bool ekf;
|
bool ekf;
|
||||||
} failsafe;
|
} 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
|
// true if we have a position estimate from AHRS
|
||||||
bool have_position;
|
bool have_position;
|
||||||
|
|
||||||
@ -496,7 +455,6 @@ public:
|
|||||||
float simple_sin_yaw;
|
float simple_sin_yaw;
|
||||||
};
|
};
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
|
||||||
extern Rover rover;
|
extern Rover rover;
|
||||||
|
|
||||||
using AP_HAL::millis;
|
using AP_HAL::millis;
|
||||||
|
Loading…
Reference in New Issue
Block a user