APM:Libraries
SIM_Motor.cpp
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 simulator class
17 */
18 
19 #include "SIM_Motor.h"
20 #include <AP_Motors/AP_Motors.h>
21 
22 using namespace SITL;
23 
24 // calculate rotational accel and thrust for a motor
26  const float thrust_scale,
27  uint8_t motor_offset,
28  Vector3f &rot_accel,
29  Vector3f &thrust)
30 {
31  // fudge factors
32  const float arm_scale = radians(5000);
33  const float yaw_scale = radians(400);
34 
35  // get motor speed from 0 to 1
36  float motor_speed = constrain_float((input.servos[motor_offset+servo]-1100)/900.0, 0, 1);
37 
38  // the yaw torque of the motor
39  Vector3f rotor_torque(0, 0, yaw_factor * motor_speed * yaw_scale);
40 
41  // get thrust for untilted motor
42  thrust(0, 0, -motor_speed);
43 
44  // define the arm position relative to center of mass
45  Vector3f arm(arm_scale * cosf(radians(angle)), arm_scale * sinf(radians(angle)), 0);
46 
47  // work out roll and pitch of motor relative to it pointing straight up
48  float roll = 0, pitch = 0;
49 
50  uint64_t now = AP_HAL::micros64();
51 
52  // possibly roll and/or pitch the motor
53  if (roll_servo >= 0) {
54  uint16_t servoval = update_servo(input.servos[roll_servo+motor_offset], now, last_roll_value);
55  if (roll_min < roll_max) {
56  roll = constrain_float(roll_min + (servoval-1000)*0.001*(roll_max-roll_min), roll_min, roll_max);
57  } else {
58  roll = constrain_float(roll_max + (2000-servoval)*0.001*(roll_min-roll_max), roll_max, roll_min);
59  }
60  }
61  if (pitch_servo >= 0) {
62  uint16_t servoval = update_servo(input.servos[pitch_servo+motor_offset], now, last_pitch_value);
63  if (pitch_min < pitch_max) {
64  pitch = constrain_float(pitch_min + (servoval-1000)*0.001*(pitch_max-pitch_min), pitch_min, pitch_max);
65  } else {
66  pitch = constrain_float(pitch_max + (2000-servoval)*0.001*(pitch_min-pitch_max), pitch_max, pitch_min);
67  }
68  }
69  last_change_usec = now;
70 
71  // possibly rotate the thrust vector and the rotor torque
72  if (!is_zero(roll) || !is_zero(pitch)) {
73  Matrix3f rotation;
74  rotation.from_euler(radians(roll), radians(pitch), 0);
75  thrust = rotation * thrust;
76  rotor_torque = rotation * rotor_torque;
77  }
78 
79  // calculate total rotational acceleration
80  rot_accel = (arm % thrust) + rotor_torque;
81 
82  // scale the thrust
83  thrust = thrust * thrust_scale;
84 }
85 
86 /*
87  update and return current value of a servo. Calculated as 1000..2000
88  */
89 uint16_t Motor::update_servo(uint16_t demand, uint64_t time_usec, float &last_value)
90 {
91  if (servo_rate <= 0) {
92  return demand;
93  }
94  if (servo_type == SERVO_RETRACT) {
95  // handle retract servos
96  if (demand > 1700) {
97  demand = 2000;
98  } else if (demand < 1300) {
99  demand = 1000;
100  } else {
101  demand = last_value;
102  }
103  }
104  demand = constrain_int16(demand, 1000, 2000);
105  float dt = (time_usec - last_change_usec) * 1.0e-6f;
106  // assume servo moves through 90 degrees over 1000 to 2000
107  float max_change = 1000 * (dt / servo_rate) * 60.0f / 90.0f;
108  last_value = constrain_float(demand, last_value-max_change, last_value+max_change);
109  return uint16_t(last_value+0.5);
110 }
float last_pitch_value
Definition: SIM_Motor.h:45
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
float yaw_factor
Definition: SIM_Motor.h:31
void from_euler(float roll, float pitch, float yaw)
Definition: matrix3.cpp:26
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
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
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
enum SITL::Motor::@208 servo_type
uint64_t micros64()
Definition: system.cpp:162
float pitch_min
Definition: SIM_Motor.h:39
float pitch_max
Definition: SIM_Motor.h:39
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
float roll_min
Definition: SIM_Motor.h:37
static constexpr float radians(float deg)
Definition: AP_Math.h:158
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