ardupilot/libraries/AP_Motors/AP_MotorsQuad.h

27 lines
762 B
C
Raw Normal View History

2013-05-29 20:51:34 -03:00
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/// @file AP_MotorsQuad.h
/// @brief Motor control class for Quadcopters
#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <RC_Channel/RC_Channel.h> // RC Channel Library
2012-10-26 20:59:07 -03:00
#include "AP_MotorsMatrix.h" // Parent Motors Matrix library
/// @class AP_MotorsQuad
class AP_MotorsQuad : public AP_MotorsMatrix {
public:
/// Constructor
AP_MotorsQuad(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
AP_MotorsMatrix(loop_rate, speed_hz)
{ };
// setup_motors - configures the motors for a quad
virtual void setup_motors();
protected:
};