2013-05-29 20:51:34 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2012-04-02 05:26:37 -03:00
|
|
|
|
|
|
|
/// @file AP_MotorsTri.h
|
|
|
|
/// @brief Motor control class for Tricopters
|
2016-02-17 21:25:38 -04:00
|
|
|
#pragma once
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2015-08-11 03:28:44 -03:00
|
|
|
#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
|
2015-07-15 04:58:43 -03:00
|
|
|
#include "AP_MotorsMulticopter.h"
|
2012-04-02 05:26:37 -03:00
|
|
|
|
|
|
|
// tail servo uses channel 7
|
2015-05-25 10:26:48 -03:00
|
|
|
#define AP_MOTORS_CH_TRI_YAW CH_7
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2016-03-25 05:56:58 -03:00
|
|
|
#define AP_MOTORS_TRI_SERVO_RANGE_DEG_MIN 5 // minimum angle movement of tail servo in degrees
|
|
|
|
#define AP_MOTORS_TRI_SERVO_RANGE_DEG_MAX 80 // maximum angle movement of tail servo in degrees
|
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
/// @class AP_MotorsTri
|
2015-07-15 04:58:43 -03:00
|
|
|
class AP_MotorsTri : public AP_MotorsMulticopter {
|
2012-08-17 03:20:27 -03:00
|
|
|
public:
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
/// Constructor
|
2015-05-14 22:00:46 -03:00
|
|
|
AP_MotorsTri(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
|
2015-07-15 04:58:43 -03:00
|
|
|
AP_MotorsMulticopter(loop_rate, speed_hz)
|
2015-05-14 22:00:46 -03:00
|
|
|
{
|
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
2012-08-17 03:20:27 -03:00
|
|
|
};
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
// init
|
2013-05-14 05:35:27 -03:00
|
|
|
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
|
2013-05-14 05:35:27 -03:00
|
|
|
void set_update_rate( uint16_t speed_hz );
|
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
|
2013-05-14 05:35:27 -03:00
|
|
|
virtual void enable();
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2014-04-28 04:30:26 -03:00
|
|
|
// output_test - spin a motor at the pwm value specified
|
|
|
|
// motor_seq is the motor's sequence number from 1 to the number of motors on the frame
|
|
|
|
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
|
|
|
|
virtual void output_test(uint8_t motor_seq, int16_t pwm);
|
2012-08-17 03:20:27 -03:00
|
|
|
|
2016-01-19 23:15:10 -04:00
|
|
|
// output_to_motors - sends minimum values out to the motors
|
|
|
|
virtual void output_to_motors();
|
|
|
|
|
2014-07-26 04:27:39 -03:00
|
|
|
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
|
|
|
|
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
|
|
|
|
virtual uint16_t get_motor_mask();
|
|
|
|
|
2015-05-14 22:00:46 -03:00
|
|
|
// var_info for holding Parameter information
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
2012-04-02 05:26:37 -03:00
|
|
|
protected:
|
2012-08-17 03:20:27 -03:00
|
|
|
// output - sends commands to the motors
|
2015-04-02 17:54:15 -03:00
|
|
|
void output_armed_stabilizing();
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2016-05-01 19:00:45 -03:00
|
|
|
// call vehicle supplied thrust compensation if set
|
|
|
|
void thrust_compensation(void) override;
|
|
|
|
|
2015-05-14 22:00:46 -03:00
|
|
|
// calc_yaw_radio_output - calculate final radio output for yaw channel
|
2016-01-19 23:14:20 -04:00
|
|
|
int16_t calc_yaw_radio_output(float yaw_input, float yaw_input_max); // calculate radio output for yaw servo, typically in range of 1100-1900
|
2015-05-14 22:00:46 -03:00
|
|
|
|
|
|
|
// parameters
|
2016-01-19 23:11:50 -04:00
|
|
|
AP_Int8 _yaw_reverse; // Reverse yaw output
|
2015-05-14 22:00:46 -03:00
|
|
|
AP_Int16 _yaw_servo_trim; // Trim or center position of yaw servo
|
2016-02-08 01:37:25 -04:00
|
|
|
AP_Int16 _yaw_servo_min; // Minimum pwm of yaw servo
|
|
|
|
AP_Int16 _yaw_servo_max; // Maximum pwm of yaw servo
|
2016-02-08 01:40:43 -04:00
|
|
|
AP_Float _yaw_servo_angle_max_deg; // Maximum lean angle of yaw servo in degrees
|
2016-01-19 23:14:20 -04:00
|
|
|
float _pivot_angle; // Angle of yaw pivot
|
|
|
|
float _thrust_right;
|
|
|
|
float _thrust_rear;
|
|
|
|
float _thrust_left;
|
2012-08-17 03:20:27 -03:00
|
|
|
};
|