54 for (
int i = 0; i < 6; i++) {
58 if (pwm < 2000 && pwm > 1000) {
59 output = (pwm - 1500) / 400.0;
63 body_accel += t.
linear * output * 2.5;
73 float terminal_rotation_rate = 10.0;
74 if (terminal_rotation_rate > 0) {
76 rot_accel.
x -=
gyro.
x *
radians(400.0) / terminal_rotation_rate;
77 rot_accel.
y -=
gyro.
y *
radians(400.0) / terminal_rotation_rate;
78 rot_accel.
z -=
gyro.
z *
radians(400.0) / terminal_rotation_rate;
81 float terminal_velocity = 3.0;
82 if (terminal_velocity > 0) {
99 if (below_water_level < 0) {
bool on_ground() const override
#define MOT_3_FORWARD_FACTOR
void update_wind(const struct sitl_input &input)
Vector3< float > Vector3f
#define MOT_1_STRAFE_FACTOR
const class SITL::Submarine::FrameConfig frame_proprietary
float bouyancy_acceleration
#define MOT_4_STRAFE_FACTOR
#define MOT_1_PITCH_FACTOR
#define MOT_2_STRAFE_FACTOR
#define MOT_3_THROTTLE_FACTOR
#define MOT_4_PITCH_FACTOR
#define MOT_3_STRAFE_FACTOR
Submarine(const char *home_str, const char *frame_str)
#define MOT_3_ROLL_FACTOR
#define MOT_4_THROTTLE_FACTOR
#define MOT_1_ROLL_FACTOR
void update(const struct sitl_input &input)
#define MOT_1_FORWARD_FACTOR
#define MOT_3_PITCH_FACTOR
#define MOT_2_THROTTLE_FACTOR
float calculate_buoyancy_acceleration()
Calculate buoyancy force of the frame.
#define MOT_4_FORWARD_FACTOR
Matrix3< T > transposed(void) const
#define MOT_4_ROLL_FACTOR
#define MOT_6_PITCH_FACTOR
#define MOT_2_ROLL_FACTOR
#define MOT_1_THROTTLE_FACTOR
#define MOT_5_THROTTLE_FACTOR
#define MOT_2_PITCH_FACTOR
void update_mag_field_bf(void)
void update_position(void)
static constexpr float radians(float deg)
#define MOT_6_THROTTLE_FACTOR
void calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel)
#define MOT_5_STRAFE_FACTOR
void update_dynamics(const Vector3f &rot_accel)
#define MOT_6_ROLL_FACTOR
#define MOT_6_STRAFE_FACTOR
#define MOT_6_FORWARD_FACTOR
static Thruster vectored_thrusters[]
#define MOT_5_FORWARD_FACTOR
#define MOT_5_ROLL_FACTOR
enum SITL::Aircraft::@199 ground_behavior
#define MOT_2_FORWARD_FACTOR
#define MOT_5_PITCH_FACTOR