ardupilot/libraries/AP_Motors/AP_MotorsTri.h

74 lines
3.0 KiB
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_MotorsTri.h
/// @brief Motor control class for Tricopters
#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
#include "AP_MotorsMulticopter.h"
// tail servo uses channel 7
2015-05-25 10:26:48 -03:00
#define AP_MOTORS_CH_TRI_YAW CH_7
#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
/// @class AP_MotorsTri
class AP_MotorsTri : public AP_MotorsMulticopter {
public:
/// Constructor
AP_MotorsTri(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
AP_MotorsMulticopter(loop_rate, speed_hz)
{
AP_Param::setup_object_defaults(this, var_info);
};
// init
virtual void Init();
// set update rate to motors - a value in hertz
void set_update_rate( uint16_t speed_hz );
// enable - starts allowing signals to be sent to motors
virtual void enable();
// 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);
// 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();
// var_info for holding Parameter information
static const struct AP_Param::GroupInfo var_info[];
protected:
// output - sends commands to the motors
void output_armed_stabilizing();
// call vehicle supplied thrust compensation if set
void thrust_compensation(void) override;
// calc_yaw_radio_output - calculate final radio output for yaw channel
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
// parameters
AP_Int8 _yaw_reverse; // Reverse yaw output
AP_Int16 _yaw_servo_trim; // Trim or center position of yaw servo
AP_Int16 _yaw_servo_min; // Minimum pwm of yaw servo
AP_Int16 _yaw_servo_max; // Maximum pwm of yaw servo
AP_Float _yaw_servo_angle_max_deg; // Maximum lean angle of yaw servo in degrees
float _pivot_angle; // Angle of yaw pivot
float _thrust_right;
float _thrust_rear;
float _thrust_left;
};