mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
uncrustify libraries/AP_Motors/AP_MotorsY6.h
This commit is contained in:
parent
4cb9f57565
commit
b8cc5ac4af
@ -11,19 +11,20 @@
|
||||
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||
#include <RC_Channel.h> // RC Channel Library
|
||||
#include <APM_RC.h> // ArduPilot Mega RC Library
|
||||
#include <AP_MotorsMatrix.h> // Parent Motors Matrix library
|
||||
#include <AP_MotorsMatrix.h> // Parent Motors Matrix library
|
||||
|
||||
#define AP_MOTORS_Y6_YAW_DIRECTION 1 // this really should be a user selectable parameter
|
||||
#define AP_MOTORS_Y6_YAW_DIRECTION 1 // this really should be a user selectable parameter
|
||||
|
||||
/// @class AP_MotorsY6
|
||||
class AP_MotorsY6 : public AP_MotorsMatrix {
|
||||
public:
|
||||
|
||||
/// Constructor
|
||||
AP_MotorsY6( uint8_t APM_version, APM_RC_Class* rc_out, RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMatrix(APM_version, rc_out, rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz) {};
|
||||
/// Constructor
|
||||
AP_MotorsY6( uint8_t APM_version, APM_RC_Class* rc_out, RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : AP_MotorsMatrix(APM_version, rc_out, rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz) {
|
||||
};
|
||||
|
||||
// setup_motors - configures the motors for a quad
|
||||
virtual void setup_motors();
|
||||
// setup_motors - configures the motors for a quad
|
||||
virtual void setup_motors();
|
||||
|
||||
protected:
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user