SIM_Gimbal.h 3.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113
  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. gimbal simulator class
  15. */
  16. #pragma once
  17. #include <AP_HAL/utility/Socket.h>
  18. #include "SIM_Aircraft.h"
  19. namespace SITL {
  20. class Gimbal {
  21. public:
  22. Gimbal(const struct sitl_fdm &_fdm);
  23. void update(void);
  24. private:
  25. const struct sitl_fdm &fdm;
  26. const char *target_address;
  27. const uint16_t target_port;
  28. // rotation matrix (gimbal body -> earth)
  29. Matrix3f dcm;
  30. // time of last update
  31. uint32_t last_update_us;
  32. // true angular rate of gimbal in body frame (rad/s)
  33. Vector3f gimbal_angular_rate;
  34. // observed angular rate (including biases)
  35. Vector3f gyro;
  36. /* joint angles, in radians. in yaw/roll/pitch order. Relative to fwd.
  37. So 0,0,0 points forward.
  38. Pi/2,0,0 means pointing right
  39. 0, Pi/2, 0 means pointing fwd, but rolled 90 degrees to right
  40. 0, 0, -Pi/2, means pointing down
  41. */
  42. Vector3f joint_angles;
  43. // physical constraints on joint angles in (roll, pitch, azimuth) order
  44. Vector3f lower_joint_limits;
  45. Vector3f upper_joint_limits;
  46. const float travelLimitGain;
  47. // true gyro bias
  48. Vector3f true_gyro_bias;
  49. // reporting variables. gimbal pushes these to vehicle code over
  50. // MAVLink at approx 100Hz
  51. // reporting period in ms
  52. const float reporting_period_ms;
  53. // integral of gyro vector over last time interval. In radians
  54. Vector3f delta_angle;
  55. // integral of accel vector over last time interval. In m/s
  56. Vector3f delta_velocity;
  57. /*
  58. control variables from the vehicle
  59. */
  60. // angular rate in rad/s. In body frame of gimbal
  61. Vector3f demanded_angular_rate;
  62. // gyro bias provided by EKF on vehicle. In rad/s.
  63. // Should be subtracted from the gyro readings to get true body
  64. // rotatation rates
  65. Vector3f supplied_gyro_bias;
  66. uint32_t last_report_us;
  67. uint32_t last_heartbeat_ms;
  68. bool seen_heartbeat;
  69. bool seen_gimbal_control;
  70. uint8_t vehicle_system_id;
  71. uint8_t vehicle_component_id;
  72. SocketAPM mav_socket;
  73. struct {
  74. // socket to telem2 on aircraft
  75. bool connected;
  76. mavlink_message_t rxmsg;
  77. mavlink_status_t status;
  78. uint8_t seq;
  79. } mavlink;
  80. uint32_t param_send_last_ms;
  81. uint8_t param_send_idx;
  82. void send_report(void);
  83. void param_send(const struct gimbal_param *p);
  84. struct gimbal_param *param_find(const char *name);
  85. };
  86. } // namespace SITL