2015-02-14 08:27:32 -04:00
|
|
|
/*
|
|
|
|
SToRM32 mount backend class
|
|
|
|
*/
|
2016-02-17 21:25:38 -04:00
|
|
|
#pragma once
|
2015-02-14 08:27:32 -04:00
|
|
|
|
2015-08-11 03:28:44 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_AHRS/AP_AHRS.h>
|
|
|
|
|
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <RC_Channel/RC_Channel.h>
|
|
|
|
#include "AP_Mount_Backend.h"
|
2020-07-24 14:01:21 -03:00
|
|
|
#if HAL_MOUNT_ENABLED
|
2015-02-14 08:27:32 -04:00
|
|
|
|
|
|
|
#define AP_MOUNT_STORM32_RESEND_MS 1000 // resend angle targets to gimbal once per second
|
2015-07-24 08:54:50 -03:00
|
|
|
#define AP_MOUNT_STORM32_SEARCH_MS 60000 // search for gimbal for 1 minute after startup
|
2015-02-14 08:27:32 -04:00
|
|
|
|
|
|
|
class AP_Mount_SToRM32 : public AP_Mount_Backend
|
|
|
|
{
|
|
|
|
|
|
|
|
public:
|
|
|
|
// Constructor
|
|
|
|
AP_Mount_SToRM32(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance);
|
|
|
|
|
|
|
|
// init - performs any required initialisation for this instance
|
2019-08-27 03:23:30 -03:00
|
|
|
void init() override {}
|
2015-02-14 08:27:32 -04:00
|
|
|
|
|
|
|
// update mount position - should be called periodically
|
2018-11-07 20:49:14 -04:00
|
|
|
void update() override;
|
2015-02-14 08:27:32 -04:00
|
|
|
|
|
|
|
// has_pan_control - returns true if this mount can control it's pan (required for multicopters)
|
2018-11-07 20:49:14 -04:00
|
|
|
bool has_pan_control() const override;
|
2015-02-14 08:27:32 -04:00
|
|
|
|
|
|
|
// set_mode - sets mount's mode
|
2018-11-07 20:49:14 -04:00
|
|
|
void set_mode(enum MAV_MOUNT_MODE mode) override;
|
2015-02-14 08:27:32 -04:00
|
|
|
|
2018-10-11 06:30:03 -03:00
|
|
|
// send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
|
2018-11-07 20:49:14 -04:00
|
|
|
void send_mount_status(mavlink_channel_t chan) override;
|
2015-02-14 08:27:32 -04:00
|
|
|
|
|
|
|
private:
|
|
|
|
|
2015-07-24 08:54:50 -03:00
|
|
|
// search for gimbal in GCS_MAVLink routing table
|
|
|
|
void find_gimbal();
|
|
|
|
|
2015-02-14 08:27:32 -04:00
|
|
|
// send_do_mount_control - send a COMMAND_LONG containing a do_mount_control message
|
|
|
|
void send_do_mount_control(float pitch_deg, float roll_deg, float yaw_deg, enum MAV_MOUNT_MODE mount_mode);
|
|
|
|
|
|
|
|
// internal variables
|
|
|
|
bool _initialised; // true once the driver has been initialised
|
2015-07-24 08:54:50 -03:00
|
|
|
uint8_t _sysid; // sysid of gimbal
|
|
|
|
uint8_t _compid; // component id of gimbal
|
2015-02-14 08:27:32 -04:00
|
|
|
mavlink_channel_t _chan; // mavlink channel used to communicate with gimbal. Currently hard-coded to Telem2
|
|
|
|
uint32_t _last_send; // system time of last do_mount_control sent to gimbal
|
|
|
|
};
|
2020-07-24 14:01:21 -03:00
|
|
|
#endif // HAL_MOUNT_ENABLED
|