2015-05-26 08:43:13 -03:00
|
|
|
/*
|
|
|
|
SToRM32 mount using serial protocol backend class
|
|
|
|
*/
|
2016-02-17 21:25:38 -04:00
|
|
|
#pragma once
|
2015-05-26 08:43:13 -03:00
|
|
|
|
2022-06-14 01:56:34 -03:00
|
|
|
#include "AP_Mount_Backend.h"
|
|
|
|
|
|
|
|
#if HAL_MOUNT_STORM32SERIAL_ENABLED
|
|
|
|
|
2015-08-11 03:28:44 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include <AP_Common/AP_Common.h>
|
2015-05-26 08:43:13 -03:00
|
|
|
|
|
|
|
#define AP_MOUNT_STORM32_SERIAL_RESEND_MS 1000 // resend angle targets to gimbal once per second
|
|
|
|
|
|
|
|
class AP_Mount_SToRM32_serial : public AP_Mount_Backend
|
|
|
|
{
|
|
|
|
|
|
|
|
public:
|
|
|
|
// Constructor
|
2023-03-05 18:09:30 -04:00
|
|
|
using AP_Mount_Backend::AP_Mount_Backend;
|
2015-05-26 08:43:13 -03:00
|
|
|
|
|
|
|
// init - performs any required initialisation for this instance
|
2019-08-27 03:23:30 -03:00
|
|
|
void init() override;
|
2015-05-26 08:43:13 -03:00
|
|
|
|
|
|
|
// update mount position - should be called periodically
|
2018-11-07 20:49:14 -04:00
|
|
|
void update() override;
|
2015-05-26 08:43:13 -03:00
|
|
|
|
2022-09-29 02:11:31 -03:00
|
|
|
// has_pan_control - returns true if this mount can control its pan (required for multicopters)
|
2022-08-26 00:42:17 -03:00
|
|
|
bool has_pan_control() const override { return yaw_range_valid(); };
|
2015-05-26 08:43:13 -03:00
|
|
|
|
2022-07-11 05:07:22 -03:00
|
|
|
protected:
|
|
|
|
|
|
|
|
// get attitude as a quaternion. returns true on success
|
|
|
|
bool get_attitude_quaternion(Quaternion& att_quat) override;
|
2015-05-26 08:43:13 -03:00
|
|
|
|
|
|
|
private:
|
|
|
|
|
2015-05-26 08:44:33 -03:00
|
|
|
// send_target_angles
|
2022-06-23 00:39:41 -03:00
|
|
|
void send_target_angles(const MountTarget& angle_target_rad);
|
2015-05-26 08:43:13 -03:00
|
|
|
|
|
|
|
// send read data request
|
|
|
|
void get_angles();
|
|
|
|
|
|
|
|
// read_incoming
|
|
|
|
void read_incoming();
|
|
|
|
void parse_reply();
|
|
|
|
|
|
|
|
enum ReplyType {
|
|
|
|
ReplyType_UNKNOWN = 0,
|
|
|
|
ReplyType_DATA,
|
|
|
|
ReplyType_ACK
|
|
|
|
};
|
|
|
|
|
|
|
|
//void add_next_reply(ReplyType reply_type);
|
|
|
|
uint8_t get_reply_size(ReplyType reply_type);
|
|
|
|
bool can_send(bool with_control);
|
|
|
|
|
|
|
|
struct PACKED SToRM32_reply_data_struct {
|
|
|
|
uint16_t state;
|
|
|
|
uint16_t status;
|
|
|
|
uint16_t status2;
|
|
|
|
|
|
|
|
uint16_t i2c_errors;
|
|
|
|
uint16_t lipo_voltage;
|
|
|
|
uint16_t systicks;
|
|
|
|
uint16_t cycle_time;
|
|
|
|
|
|
|
|
int16_t imu1_gx;
|
|
|
|
int16_t imu1_gy;
|
|
|
|
int16_t imu1_gz;
|
|
|
|
|
|
|
|
int16_t imu1_ax;
|
|
|
|
int16_t imu1_ay;
|
|
|
|
int16_t imu1_az;
|
|
|
|
|
|
|
|
int16_t ahrs_x;
|
|
|
|
int16_t ahrs_y;
|
|
|
|
int16_t ahrs_z;
|
|
|
|
|
|
|
|
int16_t imu1_pitch;
|
|
|
|
int16_t imu1_roll;
|
|
|
|
int16_t imu1_yaw;
|
|
|
|
|
|
|
|
int16_t cpid_pitch;
|
|
|
|
int16_t cpid_roll;
|
|
|
|
int16_t cpid_yaw;
|
|
|
|
|
|
|
|
uint16_t input_pitch;
|
|
|
|
uint16_t input_roll;
|
|
|
|
uint16_t input_yaw;
|
|
|
|
|
|
|
|
int16_t imu2_pitch;
|
|
|
|
int16_t imu2_roll;
|
|
|
|
int16_t imu2_yaw;
|
|
|
|
|
|
|
|
int16_t mag2_yaw;
|
|
|
|
int16_t mag2_pitch;
|
|
|
|
|
|
|
|
int16_t ahrs_imu_confidence;
|
|
|
|
|
|
|
|
uint16_t function_input_values;
|
|
|
|
|
|
|
|
uint16_t crc;
|
|
|
|
uint8_t magic;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED SToRM32_reply_ack_struct {
|
2015-08-24 22:14:48 -03:00
|
|
|
uint8_t byte1;
|
|
|
|
uint8_t byte2;
|
|
|
|
uint8_t byte3;
|
2015-05-26 08:43:13 -03:00
|
|
|
uint8_t data;
|
|
|
|
uint16_t crc;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED cmd_set_angles_struct {
|
|
|
|
uint8_t byte1;
|
|
|
|
uint8_t byte2;
|
|
|
|
uint8_t byte3;
|
|
|
|
float pitch;
|
|
|
|
float roll;
|
|
|
|
float yaw;
|
|
|
|
uint8_t flags;
|
|
|
|
uint8_t type;
|
|
|
|
uint16_t crc;
|
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
// internal variables
|
|
|
|
AP_HAL::UARTDriver *_port;
|
|
|
|
|
|
|
|
bool _initialised; // true once the driver has been initialised
|
|
|
|
uint32_t _last_send; // system time of last do_mount_control sent to gimbal
|
|
|
|
|
|
|
|
uint8_t _reply_length;
|
|
|
|
uint8_t _reply_counter;
|
2023-03-05 18:09:30 -04:00
|
|
|
ReplyType _reply_type = ReplyType_UNKNOWN;
|
2015-05-26 08:43:13 -03:00
|
|
|
|
|
|
|
|
|
|
|
union PACKED SToRM32_reply {
|
2016-06-06 10:50:53 -03:00
|
|
|
DEFINE_BYTE_ARRAY_METHODS
|
2015-05-26 08:43:13 -03:00
|
|
|
SToRM32_reply_data_struct data;
|
|
|
|
SToRM32_reply_ack_struct ack;
|
|
|
|
} _buffer;
|
|
|
|
|
|
|
|
// keep the last _current_angle values
|
|
|
|
Vector3l _current_angle;
|
|
|
|
};
|
2022-06-14 01:56:34 -03:00
|
|
|
#endif // HAL_MOUNT_STORM32SERIAL_ENABLED
|