2015-05-03 05:13:58 -03:00
|
|
|
/*
|
|
|
|
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/>.
|
|
|
|
*/
|
|
|
|
/*
|
|
|
|
rover simulator class
|
|
|
|
*/
|
|
|
|
|
2015-10-22 11:04:23 -03:00
|
|
|
#pragma once
|
2015-05-03 05:13:58 -03:00
|
|
|
|
|
|
|
#include "SIM_Aircraft.h"
|
|
|
|
|
2015-10-22 10:04:42 -03:00
|
|
|
namespace SITL {
|
|
|
|
|
2015-05-03 05:13:58 -03:00
|
|
|
/*
|
|
|
|
a rover simulator
|
|
|
|
*/
|
2015-10-22 10:15:34 -03:00
|
|
|
class SimRover : public Aircraft {
|
2015-05-03 05:13:58 -03:00
|
|
|
public:
|
2019-08-15 01:01:24 -03:00
|
|
|
SimRover(const char *frame_str);
|
2015-05-03 05:13:58 -03:00
|
|
|
|
|
|
|
/* update model by one time step */
|
2019-02-21 19:12:05 -04:00
|
|
|
void update(const struct sitl_input &input) override;
|
2015-05-03 05:13:58 -03:00
|
|
|
|
|
|
|
/* static object creator */
|
2019-08-15 01:01:24 -03:00
|
|
|
static Aircraft *create(const char *frame_str) {
|
|
|
|
return new SimRover(frame_str);
|
2015-05-04 22:49:54 -03:00
|
|
|
}
|
2015-05-03 05:13:58 -03:00
|
|
|
|
|
|
|
private:
|
2021-03-30 08:03:41 -03:00
|
|
|
float max_speed = 20.0f; // vehicle's maximum forward speed in m/s
|
|
|
|
float max_accel = 10.0f; // vehicle's maximum forward acceleration in m/s/s
|
|
|
|
float max_wheel_turn = 35.0f; // ackermann steering vehicle's maximum steering angle
|
|
|
|
float turning_circle = 1.8f; // ackermann steering vehicle's minimum turn diameter in meters
|
|
|
|
float skid_turn_rate = 140.0f; // skid-steering vehicle's maximum turn rate in deg/sec
|
|
|
|
bool skid_steering; // true if this vehicle is a skid-steering vehicle
|
2015-05-03 05:13:58 -03:00
|
|
|
|
2021-03-30 09:10:58 -03:00
|
|
|
// vectored thrust related members
|
|
|
|
bool vectored_thrust; // true if vehicle uses vectored thrust (i.e. steering controls direction of thrust)
|
|
|
|
float vectored_angle_max = 90.0f; // maximum angle (in degrees) to which thrust can be turned
|
|
|
|
float vectored_turn_rate_max = 90.0f; // maximum turn rate (in deg/sec) with full throttle angled at 90deg
|
|
|
|
|
2021-02-01 12:37:57 -04:00
|
|
|
float turn_circle(float steering) const;
|
2015-05-03 05:13:58 -03:00
|
|
|
float calc_yaw_rate(float steering, float speed);
|
|
|
|
float calc_lat_accel(float steering_angle, float speed);
|
|
|
|
};
|
|
|
|
|
2015-10-22 10:04:42 -03:00
|
|
|
} // namespace SITL
|