mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
SITL: fixed build on APM2
This commit is contained in:
parent
35d22b9d57
commit
a58a663085
@ -17,6 +17,8 @@
|
||||
parent class for aircraft simulators
|
||||
*/
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#include <AP_Common.h>
|
||||
#include "SIM_Aircraft.h"
|
||||
#include <unistd.h>
|
||||
@ -243,3 +245,4 @@ void Aircraft::set_speedup(float speedup)
|
||||
{
|
||||
setup_frame_time(rate_hz, speedup);
|
||||
}
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
@ -17,6 +17,8 @@
|
||||
helicopter simulator class
|
||||
*/
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#include "SIM_Helicopter.h"
|
||||
#include <stdio.h>
|
||||
|
||||
@ -148,3 +150,4 @@ void Helicopter::update(const struct sitl_input &input)
|
||||
// update lat/lon/altitude
|
||||
update_position();
|
||||
}
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
@ -17,6 +17,8 @@
|
||||
multicopter simulator class
|
||||
*/
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#include "SIM_Multicopter.h"
|
||||
#include <stdio.h>
|
||||
|
||||
@ -219,3 +221,4 @@ void MultiCopter::update(const struct sitl_input &input)
|
||||
// update lat/lon/altitude
|
||||
update_position();
|
||||
}
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
@ -17,6 +17,8 @@
|
||||
rover simulator class
|
||||
*/
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#include "SIM_Rover.h"
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
@ -155,3 +157,4 @@ void Rover::update(const struct sitl_input &input)
|
||||
// update lat/lon/altitude
|
||||
update_position();
|
||||
}
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
Loading…
Reference in New Issue
Block a user