ardupilot/libraries/AP_Vehicle/AP_Vehicle.h

268 lines
7.8 KiB
C
Raw Normal View History

/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
/*
this header holds a parameter structure for each vehicle type for
parameters needed by multiple libraries
*/
2019-10-17 00:47:11 -03:00
#include "ModeReason.h" // reasons can't be defined in this header due to circular loops
#include <AP_Baro/AP_Baro.h>
#include <AP_BoardConfig/AP_BoardConfig.h> // board configuration library
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
#include <AP_Button/AP_Button.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_Notify/AP_Notify.h> // Notify library
#include <AP_Param/AP_Param.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
#include <AP_Relay/AP_Relay.h> // APM relay
#include <AP_RSSI/AP_RSSI.h> // RSSI Library
#include <AP_Scheduler/AP_Scheduler.h>
#include <AP_SerialManager/AP_SerialManager.h> // Serial manager library
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
#include <AP_Camera/AP_RunCam.h>
2020-01-02 23:56:06 -04:00
#include <AP_Hott_Telem/AP_Hott_Telem.h>
2020-02-11 02:15:39 -04:00
#include <AP_ESC_Telem/AP_ESC_Telem.h>
#include <AP_GyroFFT/AP_GyroFFT.h>
2020-04-06 01:12:11 -03:00
#include <AP_VisualOdom/AP_VisualOdom.h>
class AP_Vehicle : public AP_HAL::HAL::Callbacks {
public:
2019-10-08 19:36:46 -03:00
AP_Vehicle() {
if (_singleton) {
AP_HAL::panic("Too many Vehicles");
}
AP_Param::setup_object_defaults(this, var_info);
2019-10-08 19:36:46 -03:00
_singleton = this;
}
/* Do not allow copies */
AP_Vehicle(const AP_Vehicle &other) = delete;
AP_Vehicle &operator=(const AP_Vehicle&) = delete;
static AP_Vehicle *get_singleton();
// setup() is called once during vehicle startup to initialise the
// vehicle object and the objects it contains. The
// AP_HAL_MAIN_CALLBACKS pragma creates a main(...) function
// referencing an object containing setup() and loop() functions.
// A vehicle is not expected to override setup(), but
// subclass-specific initialisation can be done in init_ardupilot
// which is called from setup().
void setup(void) override final;
// HAL::Callbacks implementation.
void loop() override final;
2019-10-17 00:47:11 -03:00
bool virtual set_mode(const uint8_t new_mode, const ModeReason reason) = 0;
2020-01-09 10:44:54 -04:00
uint8_t virtual get_mode() const = 0;
2019-10-17 00:47:11 -03:00
/*
common parameters for fixed wing aircraft
*/
struct FixedWing {
AP_Int8 throttle_min;
AP_Int8 throttle_max;
AP_Int8 throttle_slewrate;
AP_Int8 throttle_cruise;
AP_Int8 takeoff_throttle_max;
AP_Int16 airspeed_min;
AP_Int16 airspeed_max;
2016-11-17 21:07:10 -04:00
AP_Int32 airspeed_cruise_cm;
AP_Int32 min_gndspeed_cm;
AP_Int8 crash_detection_enable;
AP_Int16 roll_limit_cd;
AP_Int16 pitch_limit_max_cd;
AP_Int16 pitch_limit_min_cd;
AP_Int8 autotune_level;
AP_Int8 stall_prevention;
AP_Int16 loiter_radius;
struct Rangefinder_State {
bool in_range:1;
bool have_initial_reading:1;
bool in_use:1;
float initial_range;
float correction;
float initial_correction;
float last_stable_correction;
uint32_t last_correction_time_ms;
uint8_t in_range_count;
float height_estimate;
float last_distance;
};
// stages of flight
enum FlightStage {
FLIGHT_TAKEOFF = 1,
FLIGHT_VTOL = 2,
FLIGHT_NORMAL = 3,
FLIGHT_LAND = 4,
FLIGHT_ABORT_LAND = 7
};
};
2013-10-18 05:02:52 -03:00
/*
common parameters for multicopters
*/
struct MultiCopter {
AP_Int16 angle_max;
};
void get_common_scheduler_tasks(const AP_Scheduler::Task*& tasks, uint8_t& num_tasks);
// implementations *MUST* fill in all passed-in fields or we get
// Valgrind errors
virtual void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, uint8_t &task_count, uint32_t &log_bit) = 0;
2020-01-06 18:38:12 -04:00
/*
set the "likely flying" flag. This is not guaranteed to be
accurate, but is the vehicle codes best guess as to the whether
the vehicle is currently flying
*/
void set_likely_flying(bool b) {
if (b && !likely_flying) {
_last_flying_ms = AP_HAL::millis();
}
likely_flying = b;
}
/*
get the likely flying status. Returns true if the vehicle code
thinks we are flying at the moment. Not guaranteed to be
accurate
*/
bool get_likely_flying(void) const {
return likely_flying;
}
/*
return time in milliseconds since likely_flying was set
true. Returns zero if likely_flying is currently false
*/
uint32_t get_time_flying_ms(void) const {
if (!likely_flying) {
return 0;
}
return AP_HAL::millis() - _last_flying_ms;
}
/*
methods to control vehicle for use by scripting
*/
virtual bool start_takeoff(float alt) { return false; }
virtual bool set_target_location(const Location& target_loc) { return false; }
virtual bool set_target_velocity_NED(const Vector3f& vel_ned) { return false; }
// get target location (for use by scripting)
virtual bool get_target_location(Location& target_loc) { return false; }
protected:
virtual void init_ardupilot() = 0;
virtual void load_parameters() = 0;
virtual void set_control_channels() {}
// board specific config
AP_BoardConfig BoardConfig;
#if HAL_WITH_UAVCAN
// board specific config for CAN bus
AP_BoardConfig_CAN BoardConfig_CAN;
#endif
// main loop scheduler
AP_Scheduler scheduler{FUNCTOR_BIND_MEMBER(&AP_Vehicle::fast_loop, void)};
virtual void fast_loop();
// IMU variables
// Integration time; time last loop took to run
float G_Dt;
// sensor drivers
AP_GPS gps;
AP_Baro barometer;
Compass compass;
AP_InertialSensor ins;
AP_Button button;
RangeFinder rangefinder;
AP_RSSI rssi;
#if HAL_RUNCAM_ENABLED
AP_RunCam runcam;
#endif
#if HAL_GYROFFT_ENABLED
AP_GyroFFT gyro_fft;
#endif
AP_SerialManager serial_manager;
AP_Relay relay;
AP_ServoRelayEvents ServoRelayEvents;
// notification object for LEDs, buzzers etc (parameter set to
// false disables external leds)
AP_Notify notify;
// Inertial Navigation EKF
#if AP_AHRS_NAVEKF_AVAILABLE
AP_AHRS_NavEKF ahrs;
#else
AP_AHRS_DCM ahrs;
#endif
2020-01-02 23:56:06 -04:00
#if HAL_HOTT_TELEM_ENABLED
AP_Hott_Telem hott_telem;
#endif
2020-04-06 01:12:11 -03:00
#if HAL_VISUALODOM_ENABLED
AP_VisualOdom visual_odom;
#endif
2020-02-11 02:15:39 -04:00
AP_ESC_Telem esc_telem;
static const struct AP_Param::GroupInfo var_info[];
static const struct AP_Scheduler::Task scheduler_tasks[];
2019-10-08 19:36:46 -03:00
private:
2020-02-25 07:21:59 -04:00
// delay() callback that processing MAVLink packets
static void scheduler_delay_callback();
// if there's been a watchdog reset, notify the world via a
// statustext:
void send_watchdog_reset_statustext();
2020-02-25 07:21:59 -04:00
bool likely_flying; // true if vehicle is probably flying
uint32_t _last_flying_ms; // time when likely_flying last went true
static AP_Vehicle *_singleton;
2019-10-08 19:36:46 -03:00
};
namespace AP {
AP_Vehicle *vehicle();
};
extern const AP_HAL::HAL& hal;
extern const AP_Param::Info vehicle_var_info[];
#include "AP_Vehicle_Type.h"