1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253 |
- #pragma once
- #include "SIM_Aircraft.h"
- namespace SITL {
- class SimRover : public Aircraft {
- public:
- SimRover(const char *frame_str);
-
- void update(const struct sitl_input &input) override;
-
- static Aircraft *create(const char *frame_str) {
- return new SimRover(frame_str);
- }
- private:
- float max_speed;
- float max_accel;
- float max_wheel_turn;
- float turning_circle;
- float skid_turn_rate;
- bool skid_steering;
- float turn_circle(float steering);
- float calc_yaw_rate(float steering, float speed);
- float calc_lat_accel(float steering_angle, float speed);
- };
- }
|