2012-04-02 05:26:37 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
|
|
|
|
|
|
|
/// @file AP_MotorsMatrix.h
|
|
|
|
/// @brief Motor control class for Matrixcopters
|
|
|
|
|
2012-10-26 20:59:07 -03:00
|
|
|
#ifndef __AP_MOTORS_MATRIX_H__
|
|
|
|
#define __AP_MOTORS_MATRIX_H__
|
2012-04-02 05:26:37 -03:00
|
|
|
|
|
|
|
#include <AP_Common.h>
|
|
|
|
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
|
|
|
#include <RC_Channel.h> // RC Channel Library
|
2012-10-26 20:59:07 -03:00
|
|
|
#include "AP_Motors_Class.h"
|
2012-04-02 05:26:37 -03:00
|
|
|
|
|
|
|
#define AP_MOTORS_MATRIX_MOTOR_UNDEFINED -1
|
|
|
|
#define AP_MOTORS_MATRIX_ORDER_UNDEFINED -1
|
|
|
|
|
|
|
|
#define AP_MOTORS_MATRIX_MOTOR_CW -1
|
|
|
|
#define AP_MOTORS_MATRIX_MOTOR_CCW 1
|
|
|
|
|
2012-10-09 03:48:15 -03:00
|
|
|
#define AP_MOTORS_MATRIX_YAW_LOWER_LIMIT_PWM 100
|
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
/// @class AP_MotorsMatrix
|
|
|
|
class AP_MotorsMatrix : public AP_Motors {
|
|
|
|
public:
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
/// Constructor
|
2013-01-02 00:27:58 -04:00
|
|
|
AP_MotorsMatrix( 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_Motors(rc_roll, rc_pitch, rc_throttle, rc_yaw, speed_hz),
|
2012-08-17 03:20:27 -03:00
|
|
|
_num_motors(0) {
|
|
|
|
};
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
// init
|
|
|
|
virtual void Init();
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-09-13 09:31:13 -03:00
|
|
|
// set update rate to motors - a value in hertz
|
2012-08-17 03:20:27 -03:00
|
|
|
// you must have setup_motors before calling this
|
|
|
|
virtual void set_update_rate( uint16_t speed_hz );
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
// set frame orientation (normally + or X)
|
|
|
|
virtual void set_frame_orientation( uint8_t new_orientation );
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
// enable - starts allowing signals to be sent to motors
|
|
|
|
virtual void enable();
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
// get basic information about the platform
|
|
|
|
virtual uint8_t get_num_motors() {
|
|
|
|
return _num_motors;
|
|
|
|
};
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
// motor test
|
|
|
|
virtual void output_test();
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
// output_min - sends minimum values out to the motors
|
|
|
|
virtual void output_min();
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
// add_motor using just position and prop direction
|
2012-12-17 02:28:42 -04:00
|
|
|
virtual void add_motor(int8_t motor_num, float angle_degrees, int8_t direction, int8_t testing_order = AP_MOTORS_MATRIX_ORDER_UNDEFINED);
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
// remove_motor
|
|
|
|
virtual void remove_motor(int8_t motor_num);
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
// remove_all_motors - removes all motor definitions
|
|
|
|
virtual void remove_all_motors();
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
// setup_motors - configures the motors for a given frame type - should be overwritten by child classes
|
|
|
|
virtual void setup_motors() {
|
|
|
|
remove_all_motors();
|
|
|
|
};
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
// matrix
|
|
|
|
AP_Int8 test_order[AP_MOTORS_MAX_NUM_MOTORS]; // order of the motors in the test sequence
|
|
|
|
|
2012-04-02 05:26:37 -03:00
|
|
|
protected:
|
2012-08-17 03:20:27 -03:00
|
|
|
// output - sends commands to the motors
|
|
|
|
virtual void output_armed();
|
|
|
|
virtual void output_disarmed();
|
|
|
|
|
|
|
|
// add_motor using raw roll, pitch, throttle and yaw factors
|
2012-12-17 02:28:42 -04:00
|
|
|
virtual void add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, int8_t testing_order = AP_MOTORS_MATRIX_ORDER_UNDEFINED);
|
2012-08-17 03:20:27 -03:00
|
|
|
|
|
|
|
int8_t _num_motors; // not a very useful variable as you really need to check the motor_enabled array to see which motors are enabled
|
|
|
|
float _roll_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to roll
|
|
|
|
float _pitch_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to pitch
|
|
|
|
float _yaw_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to yaw (normally 1 or -1)
|
|
|
|
};
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-10-26 20:59:07 -03:00
|
|
|
#endif // AP_MOTORSMATRIX
|