ardupilot/libraries/AP_Mount/AP_Mount_SToRM32.h

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

47 lines
1.4 KiB
C
Raw Normal View History

2015-02-14 08:27:32 -04:00
/*
SToRM32 mount backend class
*/
#pragma once
2015-02-14 08:27:32 -04:00
2022-02-28 21:19:11 -04:00
#include "AP_Mount_Backend.h"
#if HAL_MOUNT_STORM32MAVLINK_ENABLED
#include <AP_Math/AP_Math.h>
#include <AP_Common/AP_Common.h>
2015-02-14 08:27:32 -04:00
class AP_Mount_SToRM32 : public AP_Mount_Backend
{
public:
// Constructor
using AP_Mount_Backend::AP_Mount_Backend;
2015-02-14 08:27:32 -04:00
// update mount position - should be called periodically
void update() override;
2015-02-14 08:27:32 -04:00
// 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(); }
2015-02-14 08:27:32 -04:00
protected:
// get attitude as a quaternion. returns true on success
bool get_attitude_quaternion(Quaternion& att_quat) override;
2015-02-14 08:27:32 -04:00
private:
// search for gimbal in GCS_MAVLink routing table
void find_gimbal();
// send_do_mount_control with latest angle targets
void send_do_mount_control(const MountTarget& angle_target_rad);
2015-02-14 08:27:32 -04:00
// internal variables
bool _initialised; // true once the driver has been initialised
uint8_t _sysid; // sysid of gimbal
uint8_t _compid; // component id of gimbal
mavlink_channel_t _chan = MAVLINK_COMM_0; // mavlink channel used to communicate with gimbal
2015-02-14 08:27:32 -04:00
uint32_t _last_send; // system time of last do_mount_control sent to gimbal
};
#endif // HAL_MOUNT_STORM32MAVLINK_ENABLED