mirror of https://github.com/ArduPilot/ardupilot
SITL: added a MotorBoat class
a sailboat with zero sail area
This commit is contained in:
parent
5a1a10b03f
commit
d2e75717b8
|
@ -0,0 +1,41 @@
|
|||
/*
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
This program is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/*
|
||||
MotorBoat simulator class
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "SIM_Sailboat.h"
|
||||
|
||||
namespace SITL {
|
||||
|
||||
/*
|
||||
a MotorBoat simulator. We re-use SailBoat but force motor_connected and sail_area to 0
|
||||
*/
|
||||
class MotorBoat : public Sailboat {
|
||||
public:
|
||||
MotorBoat(const char *frame_str) : Sailboat(frame_str) {
|
||||
motor_connected = true;
|
||||
sail_area = 0.0;
|
||||
}
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new MotorBoat(frame_str);
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace SITL
|
|
@ -41,7 +41,8 @@ namespace SITL {
|
|||
Sailboat::Sailboat(const char *frame_str) :
|
||||
Aircraft(frame_str),
|
||||
steering_angle_max(35),
|
||||
turning_circle(1.8)
|
||||
turning_circle(1.8),
|
||||
sail_area(1.0)
|
||||
{
|
||||
motor_connected = (strcmp(frame_str, "sailboat-motor") == 0);
|
||||
}
|
||||
|
@ -68,8 +69,8 @@ void Sailboat::calc_lift_and_drag(float wind_speed, float angle_of_attack_deg, f
|
|||
}
|
||||
|
||||
// apply scaling by wind speed
|
||||
lift *= wind_speed;
|
||||
drag *= wind_speed;
|
||||
lift *= wind_speed * sail_area;
|
||||
drag *= wind_speed * sail_area;
|
||||
}
|
||||
|
||||
// return turning circle (diameter) in meters for steering angle proportion in the range -1 to +1
|
||||
|
|
|
@ -38,6 +38,11 @@ public:
|
|||
}
|
||||
|
||||
bool on_ground() const override {return true;};
|
||||
|
||||
protected:
|
||||
bool motor_connected; // true if this frame has a motor
|
||||
float sail_area; // 1.0 for normal area
|
||||
|
||||
private:
|
||||
|
||||
// calculate the lift and drag as values from 0 to 1 given an apparent wind speed in m/s and angle-of-attack in degrees
|
||||
|
@ -69,7 +74,6 @@ private:
|
|||
Vector3f wave_gyro; // rad/s
|
||||
float wave_heave; // m/s/s
|
||||
float wave_phase; // rads
|
||||
bool motor_connected; // true if this frame has a motor
|
||||
};
|
||||
|
||||
} // namespace SITL
|
||||
|
|
Loading…
Reference in New Issue