ArduPilot开源飞控之AP_Mount_Siyi

news2024/10/8 11:41:24

ArduPilot开源飞控之AP_Mount_Siyi

  • 1. 源由
  • 2. 框架设计
    • 2.1 类和继承
    • 2.2 公共方法
    • 2.3 保护方法
    • 2.4 私有成员和方法
    • 2.5 解析状态
    • 2.6 重要成员变量
  • 3. 重要方法
    • 3.1 AP_Mount_Siyi::init
    • 3.2 AP_Mount_Siyi::update
    • 3.3 AP_Mount_Siyi::read_incoming_packets
    • 3.4 AP_Mount_Siyi::process_packet
    • 3.5 AP_Mount_Siyi::update_zoom_control
    • 3.6 AP_Mount_Backend::set_rctargeting_on_rcinput_change
  • 4. 辅助函数
    • 4.1 基本能力
    • 4.2 摄像头&红外测距功能
    • 4.3 云台操作
  • 4. 总结
  • 5. 参考资料

1. 源由

AP_Mount_Siyi主要是挂载SIYI云台,配合SIYI的产品,比如相机。

  • SIYI Gimbal Camera

目前,SIYI云台摄像头还是挺不错的,而且在开源社区也是蛮热门的。另外,有专业的团队进行代码维护,相对来说应用代码涉及的内容会更加全面。

2. 框架设计

  • 继承自 AP_Mount_Backend
  • 用于控制摄像头和万向节的类

这个类是一个复杂的云台和摄像头控制系统,提供了初始化、更新、健康检查以及各种摄像头操作(如拍照、录像、变焦、对焦等)的方法。它还定义了一些用于处理和发送数据包的私有方法和变量。

2.1 类和继承

class AP_Mount_Siyi : public AP_Mount_Backend
{
    // 使用基类构造函数
    using AP_Mount_Backend::AP_Mount_Backend;

    // 禁止拷贝构造和赋值
    CLASS_NO_COPY(AP_Mount_Siyi);
  • AP_Mount_Siyi 继承自 AP_Mount_Backend
  • 使用 using 关键字继承了基类的构造函数。
  • 使用宏 CLASS_NO_COPY 禁止类的拷贝构造和赋值操作。

2.2 公共方法

public:
    void init() override;
    void update() override;
    bool healthy() const override;
    bool has_roll_control() const override { return false; }
    bool has_pan_control() const override { return yaw_range_valid(); }
    
    bool take_picture() override;
    bool record_video(bool start_recording) override;
    bool set_zoom(ZoomType zoom_type, float zoom_value) override;
    SetFocusResult set_focus(FocusType focus_type, float focus_value) override;
    bool set_lens(uint8_t lens) override;
    bool set_camera_source(uint8_t primary_source, uint8_t secondary_source) override;
    void send_camera_information(mavlink_channel_t chan) const override;
    void send_camera_settings(mavlink_channel_t chan) const override;
    bool get_rangefinder_distance(float& distance_m) const override;
  • initupdatehealthy 等方法是重载基类的虚函数。
  • has_roll_control 返回 false,表示该设备不支持滚动控制。
  • has_pan_control 返回 yaw_range_valid() 的结果,表示是否支持平移控制。

2.3 保护方法

protected:
    bool get_attitude_quaternion(Quaternion& att_quat) override;
    bool get_angular_velocity(Vector3f& rates) override {
        rates = _current_rates_rads;
        return true;
    }
  • get_attitude_quaternion 获取姿态四元数。
  • get_angular_velocity 获取角速度,这里直接返回 _current_rates_rads

2.4 私有成员和方法

private:
    enum class SiyiCommandId { ... };
    enum class FunctionFeedbackInfo : uint8_t { ... };
    enum class PhotoFunction : uint8_t { ... };
    enum class ParseState : uint8_t { ... };
    enum class HardwareModel : uint8_t { ... } _hardware_model;
    enum class HdrStatus : uint8_t { OFF = 0, ON = 1 };
    enum class RecordingStatus : uint8_t { OFF = 0, ON = 1, NO_CARD = 2, DATA_LOSS = 3 };
    enum class GimbalMotionMode : uint8_t { LOCK = 0, FOLLOW = 1, FPV = 2 };
    enum class GimbalMountingDirection : uint8_t { UNDEFINED = 0, NORMAL = 1, UPSIDE_DOWN = 2 };
    enum class VideoOutputStatus : uint8_t { HDMI = 0, CVBS = 1 };
    
    typedef struct { ... } GimbalConfigInfo;
    static_assert(sizeof(GimbalConfigInfo) == 7, "GimbalConfigInfo must be 7 bytes");
    
    enum class CameraImageType : uint8_t { ... };

    typedef struct { ... } Version;
    typedef struct { ... } FirmwareVersion;

    void read_incoming_packets();
    void process_packet();
    bool send_packet(SiyiCommandId cmd_id, const uint8_t* databuff, uint8_t databuff_len);
    bool send_1byte_packet(SiyiCommandId cmd_id, uint8_t data_byte);
    void request_firmware_version();
    void request_hardware_id();
    void request_configuration();
    void request_function_feedback_info();
    void request_gimbal_attitude();
    void request_rangefinder_distance();
    void rotate_gimbal(int8_t pitch_scalar, int8_t yaw_scalar, bool yaw_is_ef);
    bool set_motion_mode(const GimbalMotionMode mode, const bool force=false);
    void send_target_rates(float pitch_rads, float yaw_rads, bool yaw_is_ef);
    void send_target_angles(float pitch_rad, float yaw_rad, bool yaw_is_ef);
    bool send_zoom_rate(float zoom_value);
    bool send_zoom_mult(float zoom_mult);
    float get_zoom_mult_max() const;
    void update_zoom_control();
    const char* get_model_name() const;
    void check_firmware_version() const;
    
    AP_HAL::UARTDriver *_uart;
    bool _initialised;
    bool _got_hardware_id;
    FirmwareVersion _fw_version;
    uint8_t _msg_buff[AP_MOUNT_SIYI_PACKETLEN_MAX];
    uint8_t _msg_buff_len;
    const uint8_t _msg_buff_data_start = 8;
    
    struct PACKED {
        uint16_t data_len;
        uint8_t command_id;
        uint16_t data_bytes_received;
        uint16_t crc16;
        ParseState state;
    } _parsed_msg;

    uint32_t _last_send_ms;
    uint16_t _last_seq;
    Vector3f _current_angle_rad;
    Vector3f _current_rates_rads;
    uint32_t _last_current_angle_rad_ms;
    uint32_t _last_req_current_angle_rad_ms;
    ZoomType _zoom_type;
    float _zoom_rate_target;
    float _zoom_mult;
    uint32_t _last_zoom_control_ms;
    GimbalConfigInfo _config_info;
    uint32_t _last_rangefinder_req_ms;
    uint32_t _last_rangefinder_dist_ms;
    float _rangefinder_dist_m;
    uint32_t _last_attitude_send_ms;

    void send_attitude(void);

    struct HWInfo {
        uint8_t hwid[2];
        const char* model_name;
    };
    static const HWInfo hardware_lookup_table[];
    
    uint8_t sent_time_count;
};
  • 枚举 SiyiCommandIdFunctionFeedbackInfo 等定义了各种命令和状态。
  • GimbalConfigInfo 结构体存储云台配置信息,并用 static_assert 确保其大小为 7 字节。
  • 各种私有方法用于发送、处理和读取数据包,管理云台的运动模式和摄像头的控制。

2.5 解析状态

enum class ParseState : uint8_t {
    WAITING_FOR_HEADER_LOW,
    WAITING_FOR_HEADER_HIGH,
    WAITING_FOR_CTRL,
    WAITING_FOR_DATALEN_LOW,
    WAITING_FOR_DATALEN_HIGH,
    WAITING_FOR_SEQ_LOW,
    WAITING_FOR_SEQ_HIGH,
    WAITING_FOR_CMDID,
    WAITING_FOR_DATA,
    WAITING_FOR_CRC_LOW,
    WAITING_FOR_CRC_HIGH,
};
  • ParseState 枚举表示数据包解析的不同状态。

2.6 重要成员变量

  • _uart:指向用于通信的 UART 驱动程序。
  • _initialised:标志驱动程序是否已初始化。
  • _got_hardware_id:标志是否已收到硬件 ID。
  • _fw_version:固件版本信息。
  • _msg_buff_msg_buff_len:用于存储消息缓冲区和其长度。
  • _parsed_msg:结构体,用于存储解析消息的状态。
  • _current_angle_rad_current_rates_rads:存储从云台接收到的当前角度和角速度。

3. 重要方法

3.1 AP_Mount_Siyi::init

该初始化例程在AP_Mount::init中调用。

AP_Mount_Siyi::init()
├── 定义 `serial_manager` 变量,并获取 `AP_SerialManager` 的实例
│   ├── `const AP_SerialManager& serial_manager = AP::serialmanager();`
├── 通过 `serial_manager` 查找串口并赋值给 `_uart`
│   ├── `_uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Gimbal, 0);`
│   ├── 检查 `_uart` 是否为 `nullptr`
│       ├── 如果是 `nullptr`
│       │   ├── `return;`
├── 设置 `_initialised` 为 `true`
│   ├── `_initialised = true;`
├── 调用基类的 `init()` 方法
    ├── `AP_Mount_Backend::init();`

3.2 AP_Mount_Siyi::update

该定时更新例程在AP_Mount::update中调用。

AP_Mount_Siyi::update
├── 检查是否初始化 _initialised
│   ├── 如果未初始化,立即退出
├── 读取云台的传入数据包 read_incoming_packets()
├── 获取当前时间 now_ms
├── 定期请求固件版本或配置
│   ├── 如果自上次发送以来已过1000毫秒
│   │   ├── 更新最后发送时间 _last_send_ms
│   │   ├── 如果未获取硬件ID,则请求硬件ID request_hardware_id()
│   │   ├── 否则如果固件版本未收到,则请求固件版本 request_firmware_version()
│   │   ├── 否则请求配置 request_configuration()
│   │   └── 发送UTC时间给摄像头 (AP_RTC_ENABLED)
│       └── 如果已发送时间计数 sent_time_count 小于 5
│           ├── 获取UTC时间
│           └── 发送时间数据包 send_packet()
├── 定期请求姿态 request_gimbal_attitude()
│   ├── 如果自上次请求姿态以来已过50毫秒
│       ├── 请求云台姿态
│       └── 更新最后请求姿态时间 _last_req_current_angle_rad_ms
├── 定期请求测距仪距离 request_rangefinder_distance()
│   ├── 如果硬件型号为 ZT30 且自上次请求以来已过100毫秒
│       └── 请求测距仪距离
│       └── 更新最后请求时间 _last_rangefinder_req_ms
├── 定期发送姿态 send_attitude()
│   ├── 如果自上次发送姿态以来已过100毫秒
│       ├── 更新最后发送姿态时间 _last_attitude_send_ms
│       └── 发送姿态
├── 运行变焦控制 update_zoom_control()
├── RC输入改变时切换到 RC_TARGETING 模式 set_rctargeting_on_rcinput_change()
├── 获取当前云台模式 get_mode()
│   ├── 根据模式设定目标角度或速率
│       ├── MAV_MOUNT_MODE_RETRACT 模式
│           ├── 获取收回角度 _params.retract_angles
│           ├── 设置目标类型为角度
│           └── 将角度从度转换为弧度并设置
│       ├── MAV_MOUNT_MODE_NEUTRAL 模式
│           ├── 获取中立角度 _params.neutral_angles
│           ├── 设置目标类型为角度
│           └── 将角度从度转换为弧度并设置
│       ├── MAV_MOUNT_MODE_MAVLINK_TARGETING 模式
│           └── 处理传入消息时存储MAVLINK目标
│       ├── MAV_MOUNT_MODE_RC_TARGETING 模式
│           ├── 使用飞行员的RC输入更新目标
│           ├── 获取RC目标 get_rc_target()
│           └── 根据目标类型更新角度或速率
│       ├── MAV_MOUNT_MODE_GPS_POINT 模式
│           ├── 获取指向ROI的角度目标 get_angle_target_to_roi()
│           └── 设置目标类型为角度
│       ├── MAV_MOUNT_MODE_HOME_LOCATION 模式
│           ├── 获取指向Home位置的角度目标 get_angle_target_to_home()
│           └── 设置目标类型为角度
│       ├── MAV_MOUNT_MODE_SYSID_TARGET 模式
│           ├── 获取指向其他车辆的角度目标 get_angle_target_to_sysid()
│           └── 设置目标类型为角度
│       └── 其他模式
│           └── 引发内部错误 INTERNAL_ERROR()
├── 根据目标类型发送目标角度或速率
│   ├── 目标类型为角度
│       └── 发送目标角度 send_target_angles()
│   └── 目标类型为速率
│       └── 发送目标速率 send_target_rates()

3.3 AP_Mount_Siyi::read_incoming_packets

AP_Mount_Siyi::update时,调用该函数,对SIYI云台串口数据报文进行解析。

AP_Mount_Siyi::read_incoming_packets
|
|-- 检查串口接口上是否有数据可读
|   |-- 获取可读的字节数 `nbytes`
|   |-- 如果没有字节可读,则返回
|
|-- 初始化重置解析器状态的标志 `reset_parser`
|
|-- 遍历接收到的每个字节
|   |-- 读取一个字节 `b`
|   |-- 将字节添加到消息缓冲区 `_msg_buff`
|   |-- 检查消息是否过长,如果过长则重置解析器状态
|
|   |-- 根据当前解析状态处理字节
|       |-- `WAITING_FOR_HEADER_LOW`
|           |-- 如果字节为头部低字节 `AP_MOUNT_SIYI_HEADER1`,则转到 `WAITING_FOR_HEADER_HIGH` 状态
|           |-- 否则,重置解析器状态
|
|       |-- `WAITING_FOR_HEADER_HIGH`
|           |-- 如果字节为头部高字节 `AP_MOUNT_SIYI_HEADER2`,则转到 `WAITING_FOR_CTRL` 状态
|           |-- 否则,重置解析器状态
|
|       |-- `WAITING_FOR_CTRL`
|           |-- 转到 `WAITING_FOR_DATALEN_LOW` 状态
|
|       |-- `WAITING_FOR_DATALEN_LOW`
|           |-- 保存数据长度低字节,转到 `WAITING_FOR_DATALEN_HIGH` 状态
|
|       |-- `WAITING_FOR_DATALEN_HIGH`
|           |-- 保存数据长度高字节,并进行数据长度合理性检查
|           |-- 如果数据长度合理,转到 `WAITING_FOR_SEQ_LOW` 状态
|           |-- 否则,重置解析器状态并输出调试信息
|
|       |-- `WAITING_FOR_SEQ_LOW`
|           |-- 转到 `WAITING_FOR_SEQ_HIGH` 状态
|
|       |-- `WAITING_FOR_SEQ_HIGH`
|           |-- 转到 `WAITING_FOR_CMDID` 状态
|
|       |-- `WAITING_FOR_CMDID`
|           |-- 保存命令ID,如果有数据则转到 `WAITING_FOR_DATA` 状态,否则转到 `WAITING_FOR_CRC_LOW` 状态
|
|       |-- `WAITING_FOR_DATA`
|           |-- 接收数据字节,如果所有数据接收完毕,则转到 `WAITING_FOR_CRC_LOW` 状态
|
|       |-- `WAITING_FOR_CRC_LOW`
|           |-- 保存CRC低字节,转到 `WAITING_FOR_CRC_HIGH` 状态
|
|       |-- `WAITING_FOR_CRC_HIGH`
|           |-- 保存CRC高字节,进行CRC校验
|           |-- 如果CRC校验成功,则处理接收到的封包 `process_packet()`
|           |-- 否则,输出调试信息
|           |-- 重置解析器状态
|
|-- 重置解析器状态
|   |-- 重置解析状态为 `WAITING_FOR_HEADER_LOW`
|   |-- 清空消息缓冲区长度 `_msg_buff_len`
|   |-- 重置 `reset_parser` 标志

3.4 AP_Mount_Siyi::process_packet

云台摄像机报文处理,支持以下命令:

  • SiyiCommandId::ACQUIRE_FIRMWARE_VERSION(0x01)
  • SiyiCommandId::HARDWARE_ID(0x02)
  • SiyiCommandId::AUTO_FOCUS(0x04)
  • SiyiCommandId::MANUAL_ZOOM_AND_AUTO_FOCUS(0x05)
  • SiyiCommandId::MANUAL_FOCUS(0x06)
  • SiyiCommandId::GIMBAL_ROTATION(0x07)
  • SiyiCommandId::CENTER(0x08)
  • SiyiCommandId::ACQUIRE_GIMBAL_CONFIG_INFO(0x0A)
  • SiyiCommandId::FUNCTION_FEEDBACK_INFO(0x0B)
  • SiyiCommandId::PHOTO(0x0C)
  • SiyiCommandId::ACQUIRE_GIMBAL_ATTITUDE(0x0D)
  • SiyiCommandId::READ_RANGEFINDER(0x15)
AP_Mount_Siyi::process_packet
└── switch ((SiyiCommandId)_parsed_msg.command_id)
    ├── case SiyiCommandId::ACQUIRE_FIRMWARE_VERSION
    │   ├── 检查 _parsed_msg.data_bytes_received 是否为 128
    │   ├── 解析并显示固件版本
    │   ├── 检查摄像机固件版本是否全为零
    │   ├── 设置 _fw_version.received 为 true
    │   ├── 显示摄像机和云台固件版本
    │   ├── 显示变焦固件版本(如果存在)
    │   └── 检查固件版本是否为最新
    ├── case SiyiCommandId::HARDWARE_ID
    │   ├── 查找硬件 ID 的前两位
    │   ├── 设置 _hardware_model
    │   └── 设置 _got_hardware_id 为 true
    ├── case SiyiCommandId::AUTO_FOCUS
    │   └── #if AP_MOUNT_SIYI_DEBUG
    │       ├── 检查 _parsed_msg.data_bytes_received 是否为 1
    │       └── 调试输出自动对焦信息
    ├── case SiyiCommandId::MANUAL_ZOOM_AND_AUTO_FOCUS
    │   ├── 检查 _parsed_msg.data_bytes_received 是否为 2
    │   └── 解析变焦倍数并调试输出
    ├── case SiyiCommandId::MANUAL_FOCUS
    │   └── #if AP_MOUNT_SIYI_DEBUG
    │       ├── 检查 _parsed_msg.data_bytes_received 是否为 1
    │       └── 调试输出手动对焦信息
    ├── case SiyiCommandId::GIMBAL_ROTATION
    │   └── #if AP_MOUNT_SIYI_DEBUG
    │       ├── 检查 _parsed_msg.data_bytes_received 是否为 1
    │       └── 调试输出云台旋转信息
    ├── case SiyiCommandId::CENTER
    │   └── #if AP_MOUNT_SIYI_DEBUG
    │       ├── 检查 _parsed_msg.data_bytes_received 是否为 1
    │       └── 调试输出居中信息
    ├── case SiyiCommandId::ACQUIRE_GIMBAL_CONFIG_INFO
    │   ├── 保存之前的录制状态
    │   ├── 更新云台配置信息
    │   ├── 如果录制状态变化,向用户警报
    │   └── 调试输出云台配置信息
    ├── case SiyiCommandId::FUNCTION_FEEDBACK_INFO
    │   ├── 检查 _parsed_msg.data_bytes_received 是否为 1
    │   ├── 解析功能反馈信息
    │   └── 根据反馈信息进行相应操作
    ├── case SiyiCommandId::PHOTO
    │   └── 不执行任何操作
    ├── case SiyiCommandId::ACQUIRE_GIMBAL_ATTITUDE
    │   ├── 检查 _parsed_msg.data_bytes_received 是否为 12
    │   ├── 更新当前角度和速率
    │   └── 解析并转换角度和速率信息
    ├── case SiyiCommandId::READ_RANGEFINDER
    │   ├── 解析测距仪距离
    │   └── 更新最后一次测距时间
    └── default
        └── 调试输出未处理的命令 ID

#if AP_MOUNT_SIYI_DEBUG
└── 如果存在意外的数据长度
    └── 调试输出意外长度信息

3.5 AP_Mount_Siyi::update_zoom_control

对摄像头使用SiyiCommandId::MANUAL_ZOOM_AND_AUTO_FOCUS进行光学调焦。

AP_Mount_Siyi::update_zoom_control
└── if (_zoom_type == ZoomType::RATE)
    ├── const uint32_t now_ms = AP_HAL::millis();
    ├── if (now_ms - _last_zoom_control_ms < 1000)
    │   └── return;
    ├── _last_zoom_control_ms = now_ms;
    ├── if (!is_zero(_zoom_rate_target))
    │   └── send_zoom_rate(_zoom_rate_target);
    └── // 如果 _zoom_rate_target 是零,则不会发送缩放率,因为这会触发自动对焦

3.6 AP_Mount_Backend::set_rctargeting_on_rcinput_change

当RC控制配置辅助功能RC_Channel::AUX_FUNC::MOUNT1_ROLLRC_Channel::AUX_FUNC::MOUNT1_PITCHRC_Channel::AUX_FUNC::MOUNT1_YAW时,可以直接通过RC功能键进行手动控制。

AP_Mount_Backend::set_rctargeting_on_rcinput_change
├── 如果 (!rc().has_valid_input())
│   └── 返回;
├── roll_ch = rc().find_channel_for_option(...)
├── pitch_ch = rc().find_channel_for_option(...)
├── yaw_ch = rc().find_channel_for_option(...)
├── 如果 (!last_rc_input.initialised)
│   └── 初始化 last_rc_input
└── 如果 (get_mode() != MAV_MOUNT_MODE_RC_TARGETING && get_mode() != MAV_MOUNT_MODE_RETRACT)
    ├── roll_dz = MAX(roll_ch->get_dead_zone(), 10)
    ├── pitch_dz = MAX(pitch_ch->get_dead_zone(), 10)
    ├── yaw_dz = MAX(yaw_ch->get_dead_zone(), 10)
    └── 如果 (遥控器输入发生变化条件)
        └── 设置模式为 MAV_MOUNT_MODE_RC_TARGETING
└── 如果 (get_mode() == MAV_MOUNT_MODE_RC_TARGETING || get_mode() == MAV_MOUNT_MODE_RETRACT)
    └── 更新 last_rc_input

4. 辅助函数

4.1 基本能力

检查SIYI云台摄像头:

  1. 健康状态(无串口通信,认为设备不健康)
  2. 是否具备roll方向旋转能力
  3. 是否具备yaw方向旋转能力

注:ZT30具备3维光学吊舱;A2 mini仅具有Pitch。

    // return true if healthy
    bool healthy() const override;

    // return true if this mount accepts roll targets
    bool has_roll_control() const override { return false; }

    // has_pan_control - returns true if this mount can control its pan (required for multicopters)
    bool has_pan_control() const override { return yaw_range_valid(); };
    // returns true if user has configured a valid yaw angle range
    // allows user to disable yaw even on 3-axis gimbal
    bool yaw_range_valid() const { return (_params.yaw_angle_min < _params.yaw_angle_max); }

4.2 摄像头&红外测距功能

  • 摄像头
    //
    // camera controls
    //

    // take a picture.  returns true on success
    bool take_picture() override;

    // start or stop video recording
    // set start_recording = true to start record, false to stop recording
    bool record_video(bool start_recording) override;

    // set zoom specified as a rate or percentage
    bool set_zoom(ZoomType zoom_type, float zoom_value) override;

    // set focus specified as rate, percentage or auto
    // focus in = -1, focus hold = 0, focus out = 1
    SetFocusResult set_focus(FocusType focus_type, float focus_value) override;

    // set camera lens as a value from 0 to 8.  ZT30 only
    bool set_lens(uint8_t lens) override;

    // set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type
    // primary and secondary sources use the AP_Camera::CameraSource enum cast to uint8_t
    bool set_camera_source(uint8_t primary_source, uint8_t secondary_source) override;

    // send camera information message to GCS
    void send_camera_information(mavlink_channel_t chan) const override;

    // send camera settings message to GCS
    void send_camera_settings(mavlink_channel_t chan) const override;
  • 红外测距
    //
    // rangefinder
    //

    // get rangefinder distance.  Returns true on success
    bool get_rangefinder_distance(float& distance_m) const override;

4.3 云台操作

  • 云台控制相关操作&功能
    // send packet to gimbal
    // returns true on success, false if outgoing serial buffer is full
    bool send_packet(SiyiCommandId cmd_id, const uint8_t* databuff, uint8_t databuff_len);
    bool send_1byte_packet(SiyiCommandId cmd_id, uint8_t data_byte);

    // request info from gimbal
    void request_firmware_version() { send_packet(SiyiCommandId::ACQUIRE_FIRMWARE_VERSION, nullptr, 0); }
    void request_hardware_id() { send_packet(SiyiCommandId::HARDWARE_ID, nullptr, 0); }
    void request_configuration() { send_packet(SiyiCommandId::ACQUIRE_GIMBAL_CONFIG_INFO, nullptr, 0); }
    void request_function_feedback_info() { send_packet(SiyiCommandId::FUNCTION_FEEDBACK_INFO, nullptr, 0); }
    void request_gimbal_attitude() { send_packet(SiyiCommandId::ACQUIRE_GIMBAL_ATTITUDE, nullptr, 0); }
    void request_rangefinder_distance() { send_packet(SiyiCommandId::READ_RANGEFINDER, nullptr, 0); }

    // rotate gimbal.  pitch_rate and yaw_rate are scalars in the range -100 ~ +100
    // yaw_is_ef should be true if gimbal should maintain an earth-frame target (aka lock)
    void rotate_gimbal(int8_t pitch_scalar, int8_t yaw_scalar, bool yaw_is_ef);

    // Set gimbal's motion mode if it has changed. Use force=true to always send.
    //   FOLLOW: roll and pitch are in earth-frame, yaw is in body-frame
    //   LOCK: roll, pitch and yaw are all in earth-frame
    //   FPV: roll, pitch and yaw are all in body-frame
    // Returns true if message successfully sent to Gimbal
    bool set_motion_mode(const GimbalMotionMode mode, const bool force=false);

    // send target pitch and yaw rates to gimbal
    // yaw_is_ef should be true if yaw_rads target is an earth frame rate, false if body_frame
    void send_target_rates(float pitch_rads, float yaw_rads, bool yaw_is_ef);

    // send target pitch and yaw angles to gimbal
    // yaw_is_ef should be true if yaw_rad target is an earth frame angle, false if body_frame
    void send_target_angles(float pitch_rad, float yaw_rad, bool yaw_is_ef);

    // send zoom rate command to camera. zoom out = -1, hold = 0, zoom in = 1
    bool send_zoom_rate(float zoom_value);

    // send zoom multiple command to camera. e.g. 1x, 10x, 30x
    bool send_zoom_mult(float zoom_mult);

    // get zoom multiple max
    float get_zoom_mult_max() const;

    // update zoom controller
    void update_zoom_control();

    // get model name string, returns nullptr if hardware id is unknown
    const char* get_model_name() const;

    // Checks that the firmware version on the Gimbal meets the minimum supported version.
    void check_firmware_version() const;

4. 总结

AP_Mount_Siyi是在云台基础上集成了摄像头、红外测距等诸多功能的复合设备。

  • 云台摄像头 串口接 飞控
  • AI模块 串口接 飞控

其中云台摄像头 串口接 飞控,走的就是本文所描述的协议。而AI模块 串口接飞控侧重的伴机电脑的目标跟踪。

在这里插入图片描述

5. 参考资料

【1】ArduPilot开源飞控系统之简单介绍
【2】ArduPilot之开源代码Task介绍
【3】ArduPilot飞控启动&运行过程简介
【4】ArduPilot之开源代码Library&Sketches设计
【5】ArduPilot之开源代码Sensor Drivers设计
【6】ArduPilot开源飞控之AP_Mount

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.coloradmin.cn/o/1916951.html

如若内容造成侵权/违法违规/事实不符,请联系多彩编程网进行投诉反馈,一经查实,立即删除!

相关文章

linux登入提示信息

目录 1.Linux 登录提示信息在操作系统中扮演着重要的角色 安全性提醒 欢迎信息 系统状态通知 政策和使用条款 技术支持信息 更新和变更通知 2.配置文件介绍 3.编辑配置文件 4.效果展示 修改前 修改后 目录 1.Linux 登录提示信息在操作系统中扮演着重要的角色 安…

vue 数据类型

文章目录 ref 创建&#xff1a;基本类型的响应式数据reactive 创建&#xff1a;对象类型的响应式数据ref 创建&#xff1a;对象类型的响应式数据ref 对比 reactive将一个响应式对象中的每一个属性&#xff0c;转换为ref对象(toRefs 与 toRef)computed (根据计算进行修改) ref 创…

Go语言---并发编程以及资源竞争(goroutine、runtime)

并发和并行 并行(parallel):指在同一时刻&#xff0c;有多条指令在多个处理器上同时执行。 并发(concurrency):指在同一时刻只能有一条指令执行,但多个进程指令被快速的轮换执行&#xff0c;使得在宏观上具有多个进程同时执行的效果&#xff0c;但在微观上并不是同时执行的&a…

华为HCIP Datacom H12-821 卷34

1.单选题 防火墙默认已经创建了一些安全区域,以下哪一个安全区域不是防火墙上默认存在的? A、Trust B、DMZ C、Internet D、Local 正确答案&#xff1a; C 解析&#xff1a; 防火墙默认情况下为我们提供了三个安全区域&#xff0c;分别是 Trust、DMZ和Untrust 2.判断题 …

8. Python3 pandas数据分析处理库

11.1 pandas的数据结构 pandas的数据结构如下图所示&#xff1a; pandas的几种数据结构有内在联系&#xff0c;可以吧DataFrame看作Series的容器&#xff0c;把Panel看作DataFrame的容器。可以像操作字典那样在这些数据结构中插入或者移除数据对象。在介绍这些数据结构之前&am…

力扣-dfs

何为深度优先搜索算法&#xff1f; 深度优先搜索算法&#xff0c;即DFS。就是找一个点&#xff0c;往下搜索&#xff0c;搜索到尽头再折回&#xff0c;走下一个路口。 695.岛屿的最大面积 695. 岛屿的最大面积 题目 给你一个大小为 m x n 的二进制矩阵 grid 。 岛屿 是由一些相…

【Git基本操作】添加文件 | 修改文件 | 及其各场景下.git目录树的变化

目录 1. 添加文件&add操作和commit操作 2. .git树状目录的变化 3. git其他操作 4. 修改文件 4.1 git status 4.2 git diff 1. 添加文件&add操作和commit操作 add操作&#xff1a;将工作区中所有文件的修改内容 添加进版本库的暂存区中。commit操作&#xff1a;…

TortoiseSVN-VisualSVNServer-软件代码文本资源版本控制管理-版本比较及差异文件

文章目录 1.VisualSVNServer安装2.TortoiseSVN安装2.1.检出2.2.提交资源2.3.更新资源2.4.返回版本2.5.比较软件可更改2.6.在此创建版本库3.TortoiseSVN版本差异文件1.VisualSVNServer安装 从官网下载,或者csdn下载链接: https://download.csdn.net/download/m0_67316550/8952…

Python酷库之旅-第三方库Pandas(015)

目录 一、用法精讲 37、pandas.read_sql函数 37-1、语法 37-2、参数 37-3、功能 37-4、返回值 37-5、说明 37-6、用法 37-6-1、数据准备 37-6-2、代码示例 37-6-3、结果输出 38、pandas.DataFrame.to_sql函数 38-1、语法 38-2、参数 38-3、功能 38-4、返回值 …

Python酷库之旅-第三方库Pandas(016)

目录 一、用法精讲 39、pandas.DataFrame.to_stata函数 39-1、语法 39-2、参数 39-3、功能 39-4、返回值 39-5、说明 39-6、用法 39-6-1、数据准备 39-6-2、代码示例 39-6-3、结果输出 40、pandas.read_stata函数 40-1、语法 40-2、参数 40-3、功能 40-4、返回…

Gmail邮件提醒通知如何设置?有哪些方法?

Gmail邮件提醒通知功能怎么样&#xff1f;通知邮件怎么有效发送&#xff1f; Gmail作为全球广泛使用的电子邮件服务&#xff0c;提供了多种邮件提醒通知功能&#xff0c;帮助用户不错过重要信息。AokSend将详细介绍如何设置Gmail邮件提醒通知&#xff0c;确保您不会错过任何重…

Mysql查询近半年每个月有多少天

Mysql 查询近6个月每个月有多少天&#xff1a; SELECT DATE_FORMAT(DATE_ADD(NOW(),INTERVAL-(CAST( help_topic_id AS SIGNED INTEGER )) MONTH ), %Y-%m) as months,DAY(LAST_DAY(CONCAT(DATE_FORMAT(DATE_ADD(NOW(),INTERVAL-(CAST( help_topic_id AS SIGNED INTEGER )) MO…

JavaScript中的Symbol类型是什么以及它的作用

聚沙成塔每天进步一点点 本文回顾 ⭐ 专栏简介JavaScript中的Symbol类型是什么以及它的作用1. 符号&#xff08;Symbol&#xff09;的创建2. 符号的特性3. 符号的作用3.1 属性名的唯一性3.2 防止属性被意外访问或修改3.3 使用内置的符号3.4 符号与属性遍历 4. 总结 ⭐ 写在最后…

光学传感器图像处理流程(二)

光学传感器图像处理流程&#xff08;二&#xff09; 2.4. 图像增强2.4.1. 彩色合成2.4.2 直方图变换2.4.3. 密度分割2.4.4. 图像间运算2.4.5. 邻域增强2.4.6. 主成分分析2.4.7. 图像融合 2.5. 裁剪与镶嵌2.5.1. 图像裁剪2.5.2. 图像镶嵌 2.6. 遥感信息提取2.6.1. 目视解译2.6.2…

AI网络爬虫022:批量下载某个网页中的全部链接

文章目录 一、介绍二、输入内容三、输出内容一、介绍 网页如下,有多个链接: 找到其中的a标签: <a hotrep="doc.overview.modules.path.0.0.1" href="https://cloud.tencent.com/document/product/1093/35681" title="产品优势">产品优…

02-图像基础-参数

在做有关图像和视频类的实际项目时&#xff0c;常常会涉及到图像的一些配置&#xff0c;下面对这些参数进行解释。 我们在电脑打开一张照片&#xff0c;可以看到一张完整的图像&#xff0c;比如一张360P的图片&#xff0c;其对应的像素点就是640*360&#xff0c;可以以左上角为…

Java---数组

乐观学习&#xff0c;乐观生活&#xff0c;才能不断前进啊&#xff01;&#xff01;&#xff01; 我的主页&#xff1a;optimistic_chen 我的专栏&#xff1a;c语言 欢迎大家访问~ 创作不易&#xff0c;大佬们点赞鼓励下吧~ 前言 无论c语言还是java数组都是重中之重&#xff0…

nasa数据集——1 度网格单元的全球月度土壤湿度统计数据

AMSR-E/Aqua level 3 global monthly Surface Soil Moisture Averages V005 (AMSRE_AVRMO) at GES DISC GES DISC 的 AMSR-E/Aqua 第 3 级全球地表土壤水分月平均值 V005 (AMSRE_AVRMO) AMSR-E/Aqua level 3 global monthly Surface Soil Moisture Standard Deviation V005 (…

基于JavaSpringBoot+Vue+uniapp微信小程序校园宿舍管理系统设计与实现(7000字论文参考+源码+LW+部署讲解)

博主介绍&#xff1a;硕士研究生&#xff0c;专注于信息化技术领域开发与管理&#xff0c;会使用java、标准c/c等开发语言&#xff0c;以及毕业项目实战✌ 从事基于java BS架构、CS架构、c/c 编程工作近16年&#xff0c;拥有近12年的管理工作经验&#xff0c;拥有较丰富的技术架…

不坑盒子是干啥的?

不坑盒子是一款专为提升办公效率设计的插件&#xff0c;它兼容Microsoft Office和WPS Office&#xff0c;支持Word、Excel、PPT等常用办公软件。这款插件自2024年初开始受到关注&#xff0c;其主要目的是为了让用户在日常办公中能够更加便捷地完成任务&#xff0c;从而提高工作…