SIM_Motor.cpp 4.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. simple electric motor simulator class
  15. */
  16. #include "SIM_Motor.h"
  17. #include <AP_Motors/AP_Motors.h>
  18. using namespace SITL;
  19. // calculate rotational accel and thrust for a motor
  20. void Motor::calculate_forces(const struct sitl_input &input,
  21. const float thrust_scale,
  22. uint8_t motor_offset,
  23. Vector3f &rot_accel,
  24. Vector3f &thrust)
  25. {
  26. // fudge factors
  27. const float arm_scale = radians(5000);
  28. const float yaw_scale = radians(400);
  29. // get motor speed from 0 to 1
  30. float motor_speed = constrain_float((input.servos[motor_offset+servo]-1100)/900.0, 0, 1);
  31. // the yaw torque of the motor
  32. Vector3f rotor_torque(0, 0, yaw_factor * motor_speed * yaw_scale);
  33. // get thrust for untilted motor
  34. thrust(0, 0, -motor_speed);
  35. // define the arm position relative to center of mass
  36. Vector3f arm(arm_scale * cosf(radians(angle)), arm_scale * sinf(radians(angle)), 0);
  37. // work out roll and pitch of motor relative to it pointing straight up
  38. float roll = 0, pitch = 0;
  39. uint64_t now = AP_HAL::micros64();
  40. // possibly roll and/or pitch the motor
  41. if (roll_servo >= 0) {
  42. uint16_t servoval = update_servo(input.servos[roll_servo+motor_offset], now, last_roll_value);
  43. if (roll_min < roll_max) {
  44. roll = constrain_float(roll_min + (servoval-1000)*0.001*(roll_max-roll_min), roll_min, roll_max);
  45. } else {
  46. roll = constrain_float(roll_max + (2000-servoval)*0.001*(roll_min-roll_max), roll_max, roll_min);
  47. }
  48. }
  49. if (pitch_servo >= 0) {
  50. uint16_t servoval = update_servo(input.servos[pitch_servo+motor_offset], now, last_pitch_value);
  51. if (pitch_min < pitch_max) {
  52. pitch = constrain_float(pitch_min + (servoval-1000)*0.001*(pitch_max-pitch_min), pitch_min, pitch_max);
  53. } else {
  54. pitch = constrain_float(pitch_max + (2000-servoval)*0.001*(pitch_min-pitch_max), pitch_max, pitch_min);
  55. }
  56. }
  57. last_change_usec = now;
  58. // possibly rotate the thrust vector and the rotor torque
  59. if (!is_zero(roll) || !is_zero(pitch)) {
  60. Matrix3f rotation;
  61. rotation.from_euler(radians(roll), radians(pitch), 0);
  62. thrust = rotation * thrust;
  63. rotor_torque = rotation * rotor_torque;
  64. }
  65. // calculate total rotational acceleration
  66. rot_accel = (arm % thrust) + rotor_torque;
  67. // scale the thrust
  68. thrust = thrust * thrust_scale;
  69. }
  70. /*
  71. update and return current value of a servo. Calculated as 1000..2000
  72. */
  73. uint16_t Motor::update_servo(uint16_t demand, uint64_t time_usec, float &last_value)
  74. {
  75. if (servo_rate <= 0) {
  76. return demand;
  77. }
  78. if (servo_type == SERVO_RETRACT) {
  79. // handle retract servos
  80. if (demand > 1700) {
  81. demand = 2000;
  82. } else if (demand < 1300) {
  83. demand = 1000;
  84. } else {
  85. demand = last_value;
  86. }
  87. }
  88. demand = constrain_int16(demand, 1000, 2000);
  89. float dt = (time_usec - last_change_usec) * 1.0e-6f;
  90. // assume servo moves through 90 degrees over 1000 to 2000
  91. float max_change = 1000 * (dt / servo_rate) * 60.0f / 90.0f;
  92. last_value = constrain_float(demand, last_value-max_change, last_value+max_change);
  93. return uint16_t(last_value+0.5);
  94. }
  95. // calculate current and voltage
  96. void Motor::current_and_voltage(const struct sitl_input &input, float &voltage, float &current,
  97. uint8_t motor_offset)
  98. {
  99. // get motor speed from 0 to 1
  100. float motor_speed = constrain_float((input.servos[motor_offset+servo]-1100)/900.0, 0, 1);
  101. // assume 10A per motor at full speed
  102. current = 10 * motor_speed;
  103. // assume 3S, and full throttle drops voltage by 0.7V
  104. if (AP::sitl()) {
  105. voltage = AP::sitl()->batt_voltage - motor_speed * 0.7;
  106. }
  107. }