ardupilot/libraries/AP_Mount/AP_Mount_MAVLink.h
Randy Mackay ace1fd8740 Mount_MAVLink: handle RC and GPS targeting in lib
Previously we expected the mount to do this but it is likely that the
first versions of MAVLink enable mounts will only be capable of pointing
at a particular angle
2015-01-29 14:05:07 +11:00

73 lines
2.4 KiB
C++

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
MAVLink enabled mount backend class
*/
#ifndef __AP_MOUNT_MAVLINK_H__
#define __AP_MOUNT_MAVLINK_H__
#include <AP_Math.h>
#include <AP_Common.h>
#include <AP_GPS.h>
#include <AP_AHRS.h>
#include <GCS_MAVLink.h>
#include <RC_Channel.h>
#include <AP_Mount_Backend.h>
#define AP_MOUNT_MAVLINK_COMPID 10 // Use hard-coded component id to communicate with gimbal, sysid is taken from globally defined mavlink_system.sysid
class AP_Mount_MAVLink : public AP_Mount_Backend
{
public:
// Constructor
AP_Mount_MAVLink(AP_Mount &frontend, uint8_t instance) :
AP_Mount_Backend(frontend, instance),
_enabled(false),
_chan(MAVLINK_COMM_0),
_last_mode(MAV_MOUNT_MODE_RETRACT)
{}
// init - performs any required initialisation for this instance
virtual void init();
// update mount position - should be called periodically
virtual void update();
// has_pan_control - returns true if this mount can control it's pan (required for multicopters)
virtual bool has_pan_control() const;
// set_mode - sets mount's mode
virtual void set_mode(enum MAV_MOUNT_MODE mode);
// set_roi_target - sets target location that mount should attempt to point towards
virtual void set_roi_target(const struct Location &target_loc);
// configure_msg - process MOUNT_CONFIGURE messages received from GCS
virtual void configure_msg(mavlink_message_t* msg);
// control_msg - process MOUNT_CONTROL messages received from GCS
virtual void control_msg(mavlink_message_t* msg);
// status_msg - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
virtual void status_msg(mavlink_channel_t chan);
private:
// find_mount - search for MAVLink enabled mount
void find_mount();
// send_angle_target - send earth-frame angle targets to mount
// set target_in_degrees to true to send degree targets, false if target in radians
void send_angle_target(const Vector3f& target, bool target_in_degrees);
// internal variables
bool _enabled; // gimbal becomes enabled once the mount has been discovered
mavlink_channel_t _chan; // telemetry channel used to communicate with mount
enum MAV_MOUNT_MODE _last_mode; // last mode sent to mount
Vector3f _last_angle_target; // last angle target sent to mount
};
#endif // __AP_MOUNT_MAVLINK_H__