2014-02-06 10:39:30 -04:00
/// @file AP_MotorsCoax.h
/// @brief Motor and Servo control class for Co-axial helicopters with two motors and two flaps
2016-02-17 21:25:38 -04:00
# pragma once
2014-02-06 08:28:55 -04: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
2017-01-03 05:56:57 -04:00
# include <SRV_Channel/SRV_Channel.h>
2015-07-15 04:57:15 -03:00
# include "AP_MotorsMulticopter.h"
2014-02-06 08:28:55 -04:00
// feedback direction
# define AP_MOTORS_COAX_POSITIVE 1
# define AP_MOTORS_COAX_NEGATIVE -1
2016-01-19 23:56:58 -04:00
# define NUM_ACTUATORS 4
2014-02-06 08:28:55 -04:00
# define AP_MOTORS_SINGLE_SPEED_DIGITAL_SERVOS 250 // update rate for digital servos
# define AP_MOTORS_SINGLE_SPEED_ANALOG_SERVOS 125 // update rate for analog servos
2014-02-06 10:39:30 -04:00
# define AP_MOTORS_COAX_SERVO_INPUT_RANGE 4500 // roll or pitch input of -4500 will cause servos to their minimum (i.e. radio_min), +4500 will move them to their maximum (i.e. radio_max)
2014-02-06 08:28:55 -04:00
/// @class AP_MotorsSingle
2015-07-15 04:57:15 -03:00
class AP_MotorsCoax : public AP_MotorsMulticopter {
2014-02-06 08:28:55 -04:00
public :
/// Constructor
2016-01-20 08:11:39 -04:00
AP_MotorsCoax ( uint16_t loop_rate , uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT ) :
2017-01-03 05:56:57 -04:00
AP_MotorsMulticopter ( loop_rate , speed_hz )
2014-02-06 08:28:55 -04:00
{
} ;
// init
2016-12-14 01:46:42 -04:00
void init ( motor_frame_class frame_class , motor_frame_type frame_type ) ;
// set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
void set_frame_class_and_type ( motor_frame_class frame_class , motor_frame_type frame_type ) ;
2014-02-06 08:28:55 -04:00
// set update rate to motors - a value in hertz
void set_update_rate ( uint16_t speed_hz ) ;
2018-04-27 13:22:07 -03:00
// output_test_seq - spin a motor at the pwm value specified
2014-04-28 04:29:30 -03:00
// 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
2018-04-27 13:22:07 -03:00
virtual void output_test_seq ( uint8_t motor_seq , int16_t pwm ) override ;
2014-02-06 08:28:55 -04:00
2016-01-19 23:57:21 -04:00
// output_to_motors - sends minimum values out to the motors
virtual void output_to_motors ( ) ;
2014-07-26 04:29:31 -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
2018-08-24 02:38:28 -03:00
uint16_t get_motor_mask ( ) override ;
2014-07-26 04:29:31 -03:00
2014-02-06 08:28:55 -04:00
protected :
// output - sends commands to the motors
2015-04-02 17:54:15 -03:00
void output_armed_stabilizing ( ) ;
2014-02-06 08:28:55 -04:00
2016-01-19 23:56:58 -04:00
float _actuator_out [ NUM_ACTUATORS ] ; // combined roll, pitch, yaw and throttle outputs to motors in 0~1 range
float _thrust_yt_ccw ;
float _thrust_yt_cw ;
2014-02-06 08:28:55 -04:00
} ;