SITL: fixed gimbal build on PX4

This commit is contained in:
Andrew Tridgell 2015-05-25 12:38:07 +10:00
parent 532839d7dd
commit 4f37926aea
2 changed files with 6 additions and 1 deletions

View File

@ -18,6 +18,7 @@
*/
#include "SIM_Aircraft.h"
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include "SIM_Gimbal.h"
#include <stdio.h>
@ -30,6 +31,7 @@ Gimbal::Gimbal(const struct sitl_fdm &_fdm) :
lower_joint_limits(radians(-40), radians(-135), radians(-7.5)),
upper_joint_limits(radians(40), radians(45), radians(7.5)),
travelLimitGain(20),
reporting_period_ms(10),
seen_heartbeat(false),
seen_gimbal_control(false),
mav_socket(false)
@ -289,3 +291,4 @@ void Gimbal::send_report(void)
delta_angle.zero();
}
}
#endif // CONFIG_HAL_BOARD

View File

@ -21,6 +21,7 @@
#define _SIM_GIMBAL_H
#include "SIM_Aircraft.h"
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <utility/Socket.h>
class Gimbal
@ -67,7 +68,7 @@ private:
// MAVLink at approx 100Hz
// reporting period in ms
static const float reporting_period_ms = 10;
const float reporting_period_ms;
// integral of gyro vector over last time interval. In radians
Vector3f delta_angle;
@ -104,5 +105,6 @@ private:
void send_report(void);
};
#endif // CONFIG_HAL_BOARD
#endif // _SIM_GIMBAL_H