|
|
|
@ -21,8 +21,11 @@
@@ -21,8 +21,11 @@
|
|
|
|
|
#include <AP_Math/AP_Math.h> |
|
|
|
|
|
|
|
|
|
#include "SITL.h" |
|
|
|
|
#include "SITL_Input.h" |
|
|
|
|
#include <AP_Terrain/AP_Terrain.h> |
|
|
|
|
|
|
|
|
|
#include "SIM_Sprayer.h" |
|
|
|
|
#include "SIM_Gripper_Servo.h" |
|
|
|
|
#include "SIM_Gripper_EPM.h" |
|
|
|
|
|
|
|
|
|
namespace SITL { |
|
|
|
|
|
|
|
|
@ -30,25 +33,9 @@ namespace SITL {
@@ -30,25 +33,9 @@ namespace SITL {
|
|
|
|
|
parent class for all simulator types |
|
|
|
|
*/ |
|
|
|
|
class Aircraft { |
|
|
|
|
friend class Gripper_Servo; |
|
|
|
|
|
|
|
|
|
public: |
|
|
|
|
Aircraft(const char *home_str, const char *frame_str); |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
structure passed in giving servo positions as PWM values in |
|
|
|
|
microseconds |
|
|
|
|
*/ |
|
|
|
|
struct sitl_input { |
|
|
|
|
uint16_t servos[16]; |
|
|
|
|
struct { |
|
|
|
|
float speed; // m/s
|
|
|
|
|
float direction; // degrees 0..360
|
|
|
|
|
float turbulence; |
|
|
|
|
float dir_z; //degrees -90..90
|
|
|
|
|
} wind; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
set simulation speedup |
|
|
|
|
*/ |
|
|
|
@ -111,7 +98,7 @@ public:
@@ -111,7 +98,7 @@ public:
|
|
|
|
|
return mag_bf; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
virtual float gross_mass() const { return mass; } |
|
|
|
|
float gross_mass() const { return mass + external_payload_mass; } |
|
|
|
|
|
|
|
|
|
const Location &get_location() const { return location; } |
|
|
|
|
|
|
|
|
@ -121,6 +108,10 @@ public:
@@ -121,6 +108,10 @@ public:
|
|
|
|
|
attitude.from_rotation_matrix(dcm); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void set_sprayer(Sprayer *_sprayer) { sprayer = _sprayer; } |
|
|
|
|
void set_gripper_servo(Gripper_Servo *_gripper) { gripper = _gripper; } |
|
|
|
|
void set_gripper_epm(Gripper_EPM *_gripper_epm) { gripper_epm = _gripper_epm; } |
|
|
|
|
|
|
|
|
|
protected: |
|
|
|
|
SITL *sitl; |
|
|
|
|
Location home; |
|
|
|
@ -129,26 +120,27 @@ protected:
@@ -129,26 +120,27 @@ protected:
|
|
|
|
|
float ground_level; |
|
|
|
|
float home_yaw; |
|
|
|
|
float frame_height; |
|
|
|
|
Matrix3f dcm; // rotation matrix, APM conventions, from body to earth
|
|
|
|
|
Vector3f gyro; // rad/s
|
|
|
|
|
Vector3f gyro_prev; // rad/s
|
|
|
|
|
Vector3f ang_accel; // rad/s/s
|
|
|
|
|
Vector3f velocity_ef; // m/s, earth frame
|
|
|
|
|
Vector3f wind_ef; // m/s, earth frame
|
|
|
|
|
Vector3f velocity_air_ef; // velocity relative to airmass, earth frame
|
|
|
|
|
Vector3f velocity_air_bf; // velocity relative to airmass, body frame
|
|
|
|
|
Vector3f position; // meters, NED from origin
|
|
|
|
|
float mass; // kg
|
|
|
|
|
Vector3f accel_body; // m/s/s NED, body frame
|
|
|
|
|
float airspeed; // m/s, apparent airspeed
|
|
|
|
|
float airspeed_pitot; // m/s, apparent airspeed, as seen by fwd pitot tube
|
|
|
|
|
Matrix3f dcm; // rotation matrix, APM conventions, from body to earth
|
|
|
|
|
Vector3f gyro; // rad/s
|
|
|
|
|
Vector3f gyro_prev; // rad/s
|
|
|
|
|
Vector3f ang_accel; // rad/s/s
|
|
|
|
|
Vector3f velocity_ef; // m/s, earth frame
|
|
|
|
|
Vector3f wind_ef; // m/s, earth frame
|
|
|
|
|
Vector3f velocity_air_ef; // velocity relative to airmass, earth frame
|
|
|
|
|
Vector3f velocity_air_bf; // velocity relative to airmass, body frame
|
|
|
|
|
Vector3f position; // meters, NED from origin
|
|
|
|
|
float mass; // kg
|
|
|
|
|
float external_payload_mass = 0.0f; // kg
|
|
|
|
|
Vector3f accel_body; // m/s/s NED, body frame
|
|
|
|
|
float airspeed; // m/s, apparent airspeed
|
|
|
|
|
float airspeed_pitot; // m/s, apparent airspeed, as seen by fwd pitot tube
|
|
|
|
|
float battery_voltage = -1.0f; |
|
|
|
|
float battery_current = 0.0f; |
|
|
|
|
float rpm1 = 0; |
|
|
|
|
float rpm2 = 0; |
|
|
|
|
uint8_t rcin_chan_count = 0; |
|
|
|
|
float rcin[8]; |
|
|
|
|
float range = -1.0f; // rangefinder detection in m
|
|
|
|
|
float range = -1.0f; // rangefinder detection in m
|
|
|
|
|
|
|
|
|
|
// Wind Turbulence simulated Data
|
|
|
|
|
float turbulence_azimuth = 0.0f; |
|
|
|
@ -175,7 +167,7 @@ protected:
@@ -175,7 +167,7 @@ protected:
|
|
|
|
|
|
|
|
|
|
// allow for AHRS_ORIENTATION
|
|
|
|
|
AP_Int8 *ahrs_orientation; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
enum { |
|
|
|
|
GROUND_BEHAVIOR_NONE = 0, |
|
|
|
|
GROUND_BEHAVIOR_NO_MOVEMENT, |
|
|
|
@ -234,7 +226,10 @@ protected:
@@ -234,7 +226,10 @@ protected:
|
|
|
|
|
|
|
|
|
|
// extrapolate sensors by a given delta time in seconds
|
|
|
|
|
void extrapolate_sensors(float delta_time); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// update external payload/sensor dynamic
|
|
|
|
|
void update_external_payload(const struct sitl_input &input); |
|
|
|
|
|
|
|
|
|
private: |
|
|
|
|
uint64_t last_time_us = 0; |
|
|
|
|
uint32_t frame_counter = 0; |
|
|
|
@ -253,6 +248,10 @@ private:
@@ -253,6 +248,10 @@ private:
|
|
|
|
|
} smoothing; |
|
|
|
|
|
|
|
|
|
LowPassFilterFloat servo_filter[4]; |
|
|
|
|
|
|
|
|
|
Sprayer *sprayer; |
|
|
|
|
Gripper_Servo *gripper; |
|
|
|
|
Gripper_EPM *gripper_epm; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
} // namespace SITL
|
|
|
|
|