mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
SITL: Improved Sub simulation
-Constrain z axis movement between -100m (seafloor) and 0m (water surface) -More accurate thruster modelling
This commit is contained in:
parent
97396e65d1
commit
b98573d55f
@ -174,7 +174,7 @@ protected:
|
|||||||
const float FEET_TO_METERS = 0.3048f;
|
const float FEET_TO_METERS = 0.3048f;
|
||||||
const float KNOTS_TO_METERS_PER_SECOND = 0.51444f;
|
const float KNOTS_TO_METERS_PER_SECOND = 0.51444f;
|
||||||
|
|
||||||
bool on_ground() const;
|
virtual bool on_ground() const;
|
||||||
|
|
||||||
// returns height above ground level in metres
|
// returns height above ground level in metres
|
||||||
float hagl() const; // metres
|
float hagl() const; // metres
|
||||||
|
@ -20,6 +20,8 @@
|
|||||||
#include <AP_Motors/AP_Motors.h>
|
#include <AP_Motors/AP_Motors.h>
|
||||||
#include "Frame_Vectored.h"
|
#include "Frame_Vectored.h"
|
||||||
|
|
||||||
|
#include <stdio.h>
|
||||||
|
|
||||||
using namespace SITL;
|
using namespace SITL;
|
||||||
|
|
||||||
static Thruster vectored_thrusters[] =
|
static Thruster vectored_thrusters[] =
|
||||||
@ -37,7 +39,7 @@ Submarine::Submarine(const char *home_str, const char *frame_str) :
|
|||||||
Aircraft(home_str, frame_str),
|
Aircraft(home_str, frame_str),
|
||||||
frame(NULL)
|
frame(NULL)
|
||||||
{
|
{
|
||||||
frame_height = 0.1;
|
frame_height = 0.0;
|
||||||
ground_behavior = GROUND_BEHAVIOR_NONE;
|
ground_behavior = GROUND_BEHAVIOR_NONE;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -45,19 +47,34 @@ Submarine::Submarine(const char *home_str, const char *frame_str) :
|
|||||||
void Submarine::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel)
|
void Submarine::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel)
|
||||||
{
|
{
|
||||||
rot_accel = Vector3f(0,0,0);
|
rot_accel = Vector3f(0,0,0);
|
||||||
body_accel = Vector3f(0,0,0);
|
|
||||||
|
// slight positive buoyancy
|
||||||
|
body_accel = Vector3f(0,0,-GRAVITY_MSS * 1.1);
|
||||||
|
|
||||||
for (int i = 0; i < 6; i++) {
|
for (int i = 0; i < 6; i++) {
|
||||||
Thruster t = vectored_thrusters[i];
|
Thruster t = vectored_thrusters[i];
|
||||||
int16_t pwm = input.servos[t.servo];
|
int16_t pwm = input.servos[t.servo];
|
||||||
float output = 0;
|
float output = 0;
|
||||||
if (pwm < 2000 && pwm > 1000) {
|
if (pwm < 2000 && pwm > 1000) {
|
||||||
output = (pwm - 1500) / 400.0f; // range -1~1
|
output = (pwm - 1500) / 400.0; // range -1~1
|
||||||
}
|
}
|
||||||
|
|
||||||
body_accel += t.linear * output * 1.2 * GRAVITY_MSS;
|
// 2.5 scalar for approximate real-life performance of T200 thruster
|
||||||
|
body_accel += t.linear * output * 2.5;
|
||||||
|
|
||||||
rot_accel += t.rotational * output;
|
rot_accel += t.rotational * output;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Limit movement at the surface of the water
|
||||||
|
if (position.z < 0 && body_accel.z < 0) {
|
||||||
|
body_accel.z = GRAVITY_MSS;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Limit movement at the sea floor
|
||||||
|
if (position.z > 100 && body_accel.z > -GRAVITY_MSS) {
|
||||||
|
body_accel.z = -GRAVITY_MSS;
|
||||||
|
}
|
||||||
|
|
||||||
float terminal_rotation_rate = 10.0;
|
float terminal_rotation_rate = 10.0;
|
||||||
if (terminal_rotation_rate > 0) {
|
if (terminal_rotation_rate > 0) {
|
||||||
// rotational air resistance
|
// rotational air resistance
|
||||||
@ -94,3 +111,11 @@ void Submarine::update(const struct sitl_input &input)
|
|||||||
// update magnetic field
|
// update magnetic field
|
||||||
update_mag_field_bf();
|
update_mag_field_bf();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
return true if we are on the ground
|
||||||
|
*/
|
||||||
|
bool Submarine::on_ground() const
|
||||||
|
{
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
@ -41,7 +41,11 @@ public:
|
|||||||
return new Submarine(home_str, frame_str);
|
return new Submarine(home_str, frame_str);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
|
bool on_ground() const override;
|
||||||
|
|
||||||
// calculate rotational and linear accelerations
|
// calculate rotational and linear accelerations
|
||||||
void calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel);
|
void calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel);
|
||||||
Frame *frame;
|
Frame *frame;
|
||||||
|
Loading…
Reference in New Issue
Block a user