Browse Source

SITL: fixed gimbal build on PX4

mission-4.1.18
Andrew Tridgell 10 years ago
parent
commit
4f37926aea
  1. 3
      libraries/SITL/SIM_Gimbal.cpp
  2. 4
      libraries/SITL/SIM_Gimbal.h

3
libraries/SITL/SIM_Gimbal.cpp

@ -18,6 +18,7 @@ @@ -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) : @@ -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) @@ -289,3 +291,4 @@ void Gimbal::send_report(void)
delta_angle.zero();
}
}
#endif // CONFIG_HAL_BOARD

4
libraries/SITL/SIM_Gimbal.h

@ -21,6 +21,7 @@ @@ -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: @@ -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: @@ -104,5 +105,6 @@ private:
void send_report(void);
};
#endif // CONFIG_HAL_BOARD
#endif // _SIM_GIMBAL_H

Loading…
Cancel
Save