APM:Libraries
SIM_Submarine.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  Submarine simulator class
17 */
18 
19 #include "SIM_Submarine.h"
20 #include <AP_Motors/AP_Motors.h>
21 #include "Frame_Vectored.h"
22 
23 #include <stdio.h>
24 
25 using namespace SITL;
26 
28 {
35 
36 };
37 
38 Submarine::Submarine(const char *home_str, const char *frame_str) :
39  Aircraft(home_str, frame_str),
40  frame(NULL)
41 {
42  frame_height = 0.0;
44 }
45 
46 // calculate rotational and linear accelerations
47 void Submarine::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel)
48 {
49  rot_accel = Vector3f(0,0,0);
50 
51  // slight positive buoyancy
52  body_accel = Vector3f(0, 0, -calculate_buoyancy_acceleration());
53 
54  for (int i = 0; i < 6; i++) {
55  Thruster t = vectored_thrusters[i];
56  int16_t pwm = input.servos[t.servo];
57  float output = 0;
58  if (pwm < 2000 && pwm > 1000) {
59  output = (pwm - 1500) / 400.0; // range -1~1
60  }
61 
62  // 2.5 scalar for approximate real-life performance of T200 thruster
63  body_accel += t.linear * output * 2.5;
64 
65  rot_accel += t.rotational * output;
66  }
67 
68  // Limit movement at the sea floor
69  if (position.z > 100 && body_accel.z > -GRAVITY_MSS) {
70  body_accel.z = -GRAVITY_MSS;
71  }
72 
73  float terminal_rotation_rate = 10.0;
74  if (terminal_rotation_rate > 0) {
75  // rotational air resistance
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;
79  }
80 
81  float terminal_velocity = 3.0;
82  if (terminal_velocity > 0) {
83  // air resistance
84  Vector3f air_resistance = -velocity_air_ef * (GRAVITY_MSS/terminal_velocity);
85  body_accel += dcm.transposed() * air_resistance;
86  }
87 }
88 
95 {
96  float below_water_level = position.z - frame_proprietary.height/2;
97 
98  // Completely above water level
99  if (below_water_level < 0) {
100  return 0.0f;
101  }
102 
103  // Completely below water level
104  if (below_water_level > frame_proprietary.height/2) {
106  }
107 
108  // bouyant force is proportional to fraction of height in water
110 };
111 
112 /*
113  update the Submarine simulation by one time step
114  */
115 void Submarine::update(const struct sitl_input &input)
116 {
117  // get wind vector setup
118  update_wind(input);
119 
120  Vector3f rot_accel;
121 
122  calculate_forces(input, rot_accel, accel_body);
123 
124  update_dynamics(rot_accel);
125 
126  // update lat/lon/altitude
127  update_position();
128  time_advance();
129 
130  // update magnetic field
132 }
133 
134 /*
135  return true if we are on the ground
136 */
138 {
139  return false;
140 }
Vector3f accel_body
Definition: SIM_Aircraft.h:142
Vector3f position
Definition: SIM_Aircraft.h:140
#define MOT_5_YAW_FACTOR
bool on_ground() const override
#define MOT_3_FORWARD_FACTOR
void update_wind(const struct sitl_input &input)
Vector3< float > Vector3f
Definition: vector3.h:246
#define MOT_1_STRAFE_FACTOR
Vector3f velocity_air_ef
Definition: SIM_Aircraft.h:138
const class SITL::Submarine::FrameConfig frame_proprietary
#define MOT_4_STRAFE_FACTOR
#define MOT_1_PITCH_FACTOR
Definition: Frame_Vectored.h:6
#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
static uint16_t pwm
Definition: RCOutput.cpp:20
#define MOT_4_THROTTLE_FACTOR
#define MOT_1_ROLL_FACTOR
Definition: Frame_Vectored.h:5
void update(const struct sitl_input &input)
#define MOT_1_FORWARD_FACTOR
Definition: Frame_Vectored.h:9
#define MOT_3_PITCH_FACTOR
#define MOT_3_YAW_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
Definition: matrix3.cpp:189
#define MOT_1_YAW_FACTOR
Definition: Frame_Vectored.h:7
#define MOT_4_ROLL_FACTOR
#define MOT_6_PITCH_FACTOR
#define GRAVITY_MSS
Definition: definitions.h:47
#define MOT_2_ROLL_FACTOR
T y
Definition: vector3.h:67
#define MOT_4_YAW_FACTOR
T z
Definition: vector3.h:67
Vector3f linear
Definition: SIM_Submarine.h:79
Vector3f rotational
Definition: SIM_Submarine.h:80
#define MOT_2_YAW_FACTOR
#define MOT_1_THROTTLE_FACTOR
Definition: Frame_Vectored.h:8
#define NULL
Definition: hal_types.h:59
#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)
Definition: AP_Math.h:158
#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_6_YAW_FACTOR
#define MOT_2_FORWARD_FACTOR
#define MOT_5_PITCH_FACTOR
T x
Definition: vector3.h:67