ardupilot/libraries/SITL/SIM_SingleCopter.h

58 lines
1.5 KiB
C
Raw Permalink Normal View History

2016-05-26 03:29:06 -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/>.
*/
/*
single copter simulator class
*/
#pragma once
#include "SIM_Aircraft.h"
#include <AP_Motors/AP_Motors.h>
namespace SITL {
/*
a single copter simulator
*/
class SingleCopter : public Aircraft {
public:
2019-08-15 01:01:24 -03:00
SingleCopter(const char *frame_str);
2016-05-26 03:29:06 -03:00
/* update model by one time step */
2019-02-21 19:12:05 -04:00
void update(const struct sitl_input &input) override;
2016-05-26 03:29:06 -03:00
/* static object creator */
2019-08-15 01:01:24 -03:00
static Aircraft *create(const char *frame_str) {
return new SingleCopter(frame_str);
2016-05-26 03:29:06 -03:00
}
private:
float terminal_rotation_rate = 4*radians(360.0f);
float hover_throttle = 0.65f;
float terminal_velocity = 40;
float rotor_rot_accel = radians(20) * AP_MOTORS_MATRIX_YAW_FACTOR_CW;
float roll_rate_max = radians(700);
float pitch_rate_max = radians(700);
float yaw_rate_max = radians(700);
float thrust_scale;
2016-05-26 04:08:27 -03:00
enum {
FRAME_SINGLE,
FRAME_COAX,
} frame_type;
2016-05-26 03:29:06 -03:00
};
} // namespace SITL