AP_Mount_SToRM32_serial.h 3.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149
  1. /*
  2. SToRM32 mount using serial protocol backend class
  3. */
  4. #pragma once
  5. #include <AP_HAL/AP_HAL.h>
  6. #include <AP_AHRS/AP_AHRS.h>
  7. #include <AP_Math/AP_Math.h>
  8. #include <AP_Common/AP_Common.h>
  9. #include <GCS_MAVLink/GCS_MAVLink.h>
  10. #include "AP_Mount_Backend.h"
  11. #define AP_MOUNT_STORM32_SERIAL_RESEND_MS 1000 // resend angle targets to gimbal once per second
  12. class AP_Mount_SToRM32_serial : public AP_Mount_Backend
  13. {
  14. public:
  15. // Constructor
  16. AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance);
  17. // init - performs any required initialisation for this instance
  18. void init() override;
  19. // update mount position - should be called periodically
  20. void update() override;
  21. // has_pan_control - returns true if this mount can control it's pan (required for multicopters)
  22. bool has_pan_control() const override;
  23. // set_mode - sets mount's mode
  24. void set_mode(enum MAV_MOUNT_MODE mode) override;
  25. // send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
  26. void send_mount_status(mavlink_channel_t chan) override;
  27. private:
  28. // send_target_angles
  29. void send_target_angles(float pitch_deg, float roll_deg, float yaw_deg);
  30. // send read data request
  31. void get_angles();
  32. // read_incoming
  33. void read_incoming();
  34. void parse_reply();
  35. enum ReplyType {
  36. ReplyType_UNKNOWN = 0,
  37. ReplyType_DATA,
  38. ReplyType_ACK
  39. };
  40. //void add_next_reply(ReplyType reply_type);
  41. uint8_t get_reply_size(ReplyType reply_type);
  42. bool can_send(bool with_control);
  43. struct PACKED SToRM32_reply_data_struct {
  44. uint16_t state;
  45. uint16_t status;
  46. uint16_t status2;
  47. uint16_t i2c_errors;
  48. uint16_t lipo_voltage;
  49. uint16_t systicks;
  50. uint16_t cycle_time;
  51. int16_t imu1_gx;
  52. int16_t imu1_gy;
  53. int16_t imu1_gz;
  54. int16_t imu1_ax;
  55. int16_t imu1_ay;
  56. int16_t imu1_az;
  57. int16_t ahrs_x;
  58. int16_t ahrs_y;
  59. int16_t ahrs_z;
  60. int16_t imu1_pitch;
  61. int16_t imu1_roll;
  62. int16_t imu1_yaw;
  63. int16_t cpid_pitch;
  64. int16_t cpid_roll;
  65. int16_t cpid_yaw;
  66. uint16_t input_pitch;
  67. uint16_t input_roll;
  68. uint16_t input_yaw;
  69. int16_t imu2_pitch;
  70. int16_t imu2_roll;
  71. int16_t imu2_yaw;
  72. int16_t mag2_yaw;
  73. int16_t mag2_pitch;
  74. int16_t ahrs_imu_confidence;
  75. uint16_t function_input_values;
  76. uint16_t crc;
  77. uint8_t magic;
  78. };
  79. struct PACKED SToRM32_reply_ack_struct {
  80. uint8_t byte1;
  81. uint8_t byte2;
  82. uint8_t byte3;
  83. uint8_t data;
  84. uint16_t crc;
  85. };
  86. struct PACKED cmd_set_angles_struct {
  87. uint8_t byte1;
  88. uint8_t byte2;
  89. uint8_t byte3;
  90. float pitch;
  91. float roll;
  92. float yaw;
  93. uint8_t flags;
  94. uint8_t type;
  95. uint16_t crc;
  96. };
  97. // internal variables
  98. AP_HAL::UARTDriver *_port;
  99. bool _initialised; // true once the driver has been initialised
  100. uint32_t _last_send; // system time of last do_mount_control sent to gimbal
  101. uint8_t _reply_length;
  102. uint8_t _reply_counter;
  103. ReplyType _reply_type;
  104. union PACKED SToRM32_reply {
  105. DEFINE_BYTE_ARRAY_METHODS
  106. SToRM32_reply_data_struct data;
  107. SToRM32_reply_ack_struct ack;
  108. } _buffer;
  109. // keep the last _current_angle values
  110. Vector3l _current_angle;
  111. };