Tools: add AP_Camera to list of libraries
remove dummy Camera methods from Replay add rcmapper to replay make replay a vehicle
This commit is contained in:
parent
3cba76123b
commit
30878553d6
@ -132,6 +132,10 @@ void ReplayVehicle::setup(void)
|
|||||||
ins.set_hil_mode();
|
ins.set_hil_mode();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void ReplayVehicle::loop()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
Replay replay(replayvehicle);
|
Replay replay(replayvehicle);
|
||||||
|
|
||||||
void Replay::usage(void)
|
void Replay::usage(void)
|
||||||
@ -966,10 +970,6 @@ GCS_Dummy _gcs;
|
|||||||
#include <AP_Avoidance/AP_Avoidance.h>
|
#include <AP_Avoidance/AP_Avoidance.h>
|
||||||
|
|
||||||
// dummy methods to avoid linking with these libraries
|
// dummy methods to avoid linking with these libraries
|
||||||
AP_Camera *AP::camera() { return nullptr; }
|
|
||||||
void AP_Camera::send_feedback(mavlink_channel_t) {}
|
|
||||||
void AP_Camera::control(float, float, float, float, float, float) {}
|
|
||||||
void AP_Camera::configure(float, float, float, float, float, float, float) {}
|
|
||||||
bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) { return false; }
|
bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) { return false; }
|
||||||
AP_AdvancedFailsafe *AP::advancedfailsafe() { return nullptr; }
|
AP_AdvancedFailsafe *AP::advancedfailsafe() { return nullptr; }
|
||||||
|
|
||||||
|
@ -49,12 +49,16 @@
|
|||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
#include <AP_HAL/utility/getopt_cpp.h>
|
#include <AP_HAL/utility/getopt_cpp.h>
|
||||||
|
|
||||||
class ReplayVehicle {
|
class ReplayVehicle : public AP_Vehicle {
|
||||||
public:
|
public:
|
||||||
ReplayVehicle() { unused = -1; }
|
ReplayVehicle() { unused = -1; }
|
||||||
void setup();
|
// HAL::Callbacks implementation.
|
||||||
|
void setup() override;
|
||||||
|
void loop() override;
|
||||||
void load_parameters(void);
|
void load_parameters(void);
|
||||||
|
|
||||||
|
virtual bool set_mode(const uint8_t new_mode, const ModeReason reason) override { return true; }
|
||||||
|
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
AP_Baro barometer;
|
AP_Baro barometer;
|
||||||
AP_GPS gps;
|
AP_GPS gps;
|
||||||
|
@ -15,6 +15,7 @@ def build(bld):
|
|||||||
ap_libraries=bld.ap_common_vehicle_libraries() + [
|
ap_libraries=bld.ap_common_vehicle_libraries() + [
|
||||||
'AP_Beacon',
|
'AP_Beacon',
|
||||||
'AP_Arming',
|
'AP_Arming',
|
||||||
|
'AP_RCMapper',
|
||||||
],
|
],
|
||||||
)
|
)
|
||||||
|
|
||||||
|
@ -25,6 +25,7 @@ COMMON_VEHICLE_DEPENDENT_LIBRARIES = [
|
|||||||
'AP_Baro',
|
'AP_Baro',
|
||||||
'AP_BattMonitor',
|
'AP_BattMonitor',
|
||||||
'AP_BoardConfig',
|
'AP_BoardConfig',
|
||||||
|
'AP_Camera',
|
||||||
'AP_Common',
|
'AP_Common',
|
||||||
'AP_Compass',
|
'AP_Compass',
|
||||||
'AP_Declination',
|
'AP_Declination',
|
||||||
|
Loading…
Reference in New Issue
Block a user