APM:Libraries
SIM_Motor.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  simple electric motor simulation class
17 */
18 
19 #pragma once
20 
21 #include "SIM_Aircraft.h"
22 
23 namespace SITL {
24 
25 /*
26  class to describe a motor position
27  */
28 class Motor {
29 public:
30  float angle;
31  float yaw_factor;
32  uint8_t servo;
33  uint8_t display_order;
34 
35  // support for tilting motors
36  int8_t roll_servo = -1;
38  int8_t pitch_servo = -1;
40 
41  // support for servo slew rate
43  float servo_rate = 0.24; // seconds per 60 degrees
44  uint64_t last_change_usec;
46 
47  Motor(uint8_t _servo, float _angle, float _yaw_factor, uint8_t _display_order) :
48  servo(_servo), // what servo output drives this motor
49  angle(_angle), // angle in degrees from front
50  yaw_factor(_yaw_factor), // positive is clockwise
51  display_order(_display_order) // order for clockwise display
52  {}
53 
54  /*
55  alternative constructor for tiltable motors
56  */
57  Motor(uint8_t _servo, float _angle, float _yaw_factor, uint8_t _display_order,
58  int8_t _roll_servo, float _roll_min, float _roll_max,
59  int8_t _pitch_servo, float _pitch_min, float _pitch_max) :
60  servo(_servo), // what servo output drives this motor
61  angle(_angle), // angle in degrees from front
62  yaw_factor(_yaw_factor), // positive is clockwise
63  display_order(_display_order), // order for clockwise display
64  roll_servo(_roll_servo),
65  roll_min(_roll_min),
66  roll_max(_roll_max),
67  pitch_servo(_pitch_servo),
68  pitch_min(_pitch_min),
69  pitch_max(_pitch_max)
70  {}
71 
72  void calculate_forces(const Aircraft::sitl_input &input,
73  float thrust_scale,
74  uint8_t motor_offset,
75  Vector3f &rot_accel, // rad/sec
76  Vector3f &body_thrust); // Z is down
77 
78  uint16_t update_servo(uint16_t demand, uint64_t time_usec, float &last_value);
79 };
80 }
float last_pitch_value
Definition: SIM_Motor.h:45
Motor(uint8_t _servo, float _angle, float _yaw_factor, uint8_t _display_order, int8_t _roll_servo, float _roll_min, float _roll_max, int8_t _pitch_servo, float _pitch_min, float _pitch_max)
Definition: SIM_Motor.h:57
Motor(uint8_t _servo, float _angle, float _yaw_factor, uint8_t _display_order)
Definition: SIM_Motor.h:47
float yaw_factor
Definition: SIM_Motor.h:31
float servo_rate
Definition: SIM_Motor.h:43
float roll_max
Definition: SIM_Motor.h:37
float last_roll_value
Definition: SIM_Motor.h:45
uint8_t display_order
Definition: SIM_Motor.h:33
int8_t pitch_servo
Definition: SIM_Motor.h:38
void calculate_forces(const Aircraft::sitl_input &input, float thrust_scale, uint8_t motor_offset, Vector3f &rot_accel, Vector3f &body_thrust)
Definition: SIM_Motor.cpp:25
enum SITL::Motor::@208 servo_type
float pitch_min
Definition: SIM_Motor.h:39
float pitch_max
Definition: SIM_Motor.h:39
float roll_min
Definition: SIM_Motor.h:37
uint16_t update_servo(uint16_t demand, uint64_t time_usec, float &last_value)
Definition: SIM_Motor.cpp:89
uint64_t last_change_usec
Definition: SIM_Motor.h:44
uint8_t servo
Definition: SIM_Motor.h:32
static uint16_t last_value[MAX_CHANNELS]
Definition: RCInput.cpp:15
float angle
Definition: SIM_Motor.h:30
int8_t roll_servo
Definition: SIM_Motor.h:36