APM:Libraries
SIM_Submarine.h
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  ROV/AUV/Submarine simulator class
17 */
18 
19 #pragma once
20 
21 #include "SIM_Aircraft.h"
22 #include "SIM_Motor.h"
23 #include "SIM_Frame.h"
24 
25 namespace SITL {
26 
27 /*
28  a submarine simulator
29  */
30 
31 
32 class Submarine : public Aircraft {
33 public:
34  Submarine(const char *home_str, const char *frame_str);
35 
36  /* update model by one time step */
37  void update(const struct sitl_input &input);
38 
39  /* static object creator */
40  static Aircraft *create(const char *home_str, const char *frame_str) {
41  return new Submarine(home_str, frame_str);
42  }
43 
44 
45 protected:
46  const float water_density = 1023.6; // (kg/m^3) At a temperature of 25 °C, salinity of 35 g/kg and 1 atm pressure
47 
48  const class FrameConfig {
49  public:
50  FrameConfig() = default;
51  float length = 0.457; // x direction (meters)
52  float width = 0.338; // y direction (meters)
53  float height = 0.254; // z direction (meters)
54  float weight = 10.5; // (kg)
55  float net_bouyancy = 2.0; // (N)
56 
57  float bouyancy_acceleration = GRAVITY_MSS + net_bouyancy/weight;
59 
60  bool on_ground() const override;
61 
62  // calculate rotational and linear accelerations
63  void calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel);
64  // calculate buoyancy
66 
68 };
69 
70 class Thruster {
71 public:
72  Thruster(int8_t _servo, float roll_fac, float pitch_fac, float yaw_fac, float throttle_fac, float forward_fac, float lat_fac) :
73  servo(_servo)
74  {
75  linear = Vector3f(forward_fac, lat_fac, -throttle_fac);
76  rotational = Vector3f(roll_fac, pitch_fac, yaw_fac);
77  };
78  int8_t servo;
81 };
82 }
bool on_ground() const override
Vector3< float > Vector3f
Definition: vector3.h:246
const class SITL::Submarine::FrameConfig frame_proprietary
Submarine(const char *home_str, const char *frame_str)
void update(const struct sitl_input &input)
float calculate_buoyancy_acceleration()
Calculate buoyancy force of the frame.
#define GRAVITY_MSS
Definition: definitions.h:47
Vector3f linear
Definition: SIM_Submarine.h:79
Vector3f rotational
Definition: SIM_Submarine.h:80
void calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel)
static Aircraft * create(const char *home_str, const char *frame_str)
Definition: SIM_Submarine.h:40
Thruster(int8_t _servo, float roll_fac, float pitch_fac, float yaw_fac, float throttle_fac, float forward_fac, float lat_fac)
Definition: SIM_Submarine.h:72
const float water_density
Definition: SIM_Submarine.h:46