2015-01-08 16:11:26 -04:00
|
|
|
/*
|
|
|
|
MAVLink enabled mount backend class
|
|
|
|
*/
|
2016-02-17 21:25:38 -04:00
|
|
|
#pragma once
|
2015-12-30 22:19:52 -04:00
|
|
|
|
2015-01-08 16:11:26 -04:00
|
|
|
|
2015-08-11 03:28:44 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_AHRS/AP_AHRS.h>
|
2015-01-30 02:39:31 -04:00
|
|
|
|
2020-07-24 14:01:21 -03:00
|
|
|
#include "AP_Mount_Backend.h"
|
|
|
|
#if HAL_SOLO_GIMBAL_ENABLED
|
2015-08-11 03:28:44 -03:00
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
|
|
|
#include <RC_Channel/RC_Channel.h>
|
2015-12-30 22:19:52 -04:00
|
|
|
#include "SoloGimbal.h"
|
|
|
|
|
2015-01-08 16:11:26 -04:00
|
|
|
|
2015-12-30 22:19:52 -04:00
|
|
|
class AP_Mount_SoloGimbal : public AP_Mount_Backend
|
2015-01-08 16:11:26 -04:00
|
|
|
{
|
|
|
|
|
|
|
|
public:
|
|
|
|
// Constructor
|
2015-12-30 22:19:52 -04:00
|
|
|
AP_Mount_SoloGimbal(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance);
|
2015-01-08 16:11:26 -04:00
|
|
|
|
|
|
|
// init - performs any required initialisation for this instance
|
2019-08-27 03:23:30 -03:00
|
|
|
void init() override;
|
2015-01-08 16:11:26 -04:00
|
|
|
|
|
|
|
// update mount position - should be called periodically
|
2018-11-07 20:49:14 -04:00
|
|
|
void update() override;
|
2015-01-08 16:11:26 -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-01-08 16:11:26 -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-01-08 16:11:26 -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-01-08 16:11:26 -04:00
|
|
|
|
2015-01-29 05:01:55 -04:00
|
|
|
// handle a GIMBAL_REPORT message
|
2019-04-30 07:22:48 -03:00
|
|
|
void handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg) override;
|
|
|
|
void handle_gimbal_torque_report(mavlink_channel_t chan, const mavlink_message_t &msg);
|
|
|
|
void handle_param_value(const mavlink_message_t &msg) override;
|
2015-01-29 05:01:55 -04:00
|
|
|
|
|
|
|
// send a GIMBAL_REPORT message to the GCS
|
2018-10-11 06:30:03 -03:00
|
|
|
void send_gimbal_report(mavlink_channel_t chan) override;
|
2015-01-29 05:01:55 -04:00
|
|
|
|
2018-11-07 20:49:14 -04:00
|
|
|
void update_fast() override;
|
2015-12-30 22:19:52 -04:00
|
|
|
|
2015-01-08 16:11:26 -04:00
|
|
|
private:
|
|
|
|
// internal variables
|
2015-01-19 09:39:13 -04:00
|
|
|
bool _initialised; // true once the driver has been initialised
|
2015-03-20 17:19:34 -03:00
|
|
|
|
2015-12-30 22:19:52 -04:00
|
|
|
// Write a gimbal measurament and estimation data packet
|
|
|
|
void Log_Write_Gimbal(SoloGimbal &gimbal);
|
|
|
|
|
|
|
|
bool _params_saved;
|
|
|
|
|
|
|
|
SoloGimbal _gimbal;
|
2015-01-08 16:11:26 -04:00
|
|
|
};
|
2015-02-16 01:48:55 -04:00
|
|
|
|
2020-07-24 14:01:21 -03:00
|
|
|
#endif // HAL_SOLO_GIMBAL_ENABLED
|