Mount_MAVLink: use SerialManager for init

use serial_manager's get_mavlink_channel
This commit is contained in:
Randy Mackay 2015-01-19 22:39:13 +09:00 committed by Andrew Tridgell
parent 4848b03ac6
commit d6433266d2
2 changed files with 24 additions and 4 deletions

View File

@ -1,16 +1,24 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_Mount_MAVLink.h>
#include <GCS_MAVLink.h>
// init - performs any required initialisation for this instance
void AP_Mount_MAVLink::init()
void AP_Mount_MAVLink::init(const AP_SerialManager& serial_manager)
{
// do nothing
// use mavlink channel associated with MAVLink2 protocol
if (serial_manager.get_mavlink_channel(AP_SerialManager::SerialProtocol_MAVLink2, _chan)) {
_initialised = true;
}
}
// update mount position - should be called periodically
void AP_Mount_MAVLink::update()
{
// exit immediately if not initialised
if (!_initialised) {
return;
}
// update based on mount mode
switch(_frontend.get_mode(_instance)) {
@ -60,6 +68,11 @@ bool AP_Mount_MAVLink::has_pan_control() const
// set_mode - sets mount's mode
void AP_Mount_MAVLink::set_mode(enum MAV_MOUNT_MODE mode)
{
// exit immediately if not initialised
if (!_initialised) {
return;
}
// map requested mode to mode that mount can actually support
enum MAV_MOUNT_MODE mode_to_send = mode;
switch (mode) {
@ -98,6 +111,11 @@ void AP_Mount_MAVLink::status_msg(mavlink_channel_t chan)
// send_angle_target - send earth-frame angle targets to mount
void AP_Mount_MAVLink::send_angle_target(const Vector3f& target, bool target_in_degrees)
{
// exit immediately if not initialised
if (!_initialised) {
return;
}
// convert to degrees if necessary
Vector3f target_deg = target;
if (!target_in_degrees) {

View File

@ -24,12 +24,13 @@ public:
// Constructor
AP_Mount_MAVLink(AP_Mount &frontend, AP_Mount::mount_state state, uint8_t instance) :
AP_Mount_Backend(frontend, state, instance),
_initialised(false),
_chan(MAVLINK_COMM_0),
_last_mode(MAV_MOUNT_MODE_RETRACT)
{}
// init - performs any required initialisation for this instance
virtual void init();
virtual void init(const AP_SerialManager& serial_manager);
// update mount position - should be called periodically
virtual void update();
@ -49,6 +50,7 @@ private:
void send_angle_target(const Vector3f& target, bool target_in_degrees);
// internal variables
bool _initialised; // true once the driver has been initialised
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