2013-08-29 02:34:34 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
2012-04-02 05:26:37 -03:00
|
|
|
/*
|
2012-08-17 03:20:26 -03:00
|
|
|
* AP_Motors.cpp - ArduCopter motors library
|
|
|
|
* Code by RandyMackay. DIYDrones.com
|
|
|
|
*
|
|
|
|
*/
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-10-26 20:59:07 -03:00
|
|
|
#include "AP_Motors_Class.h"
|
2015-08-11 03:28:44 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2017-01-03 05:56:57 -04:00
|
|
|
#include <SRV_Channel/SRV_Channel.h>
|
2017-04-17 05:15:55 -03:00
|
|
|
#include <GCS_MAVLink/GCS.h>
|
2017-01-03 05:56:57 -04:00
|
|
|
|
2012-10-26 20:59:07 -03:00
|
|
|
extern const AP_HAL::HAL& hal;
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2018-03-21 21:45:52 -03:00
|
|
|
// singleton instance
|
|
|
|
AP_Motors *AP_Motors::_instance;
|
|
|
|
|
2012-08-17 03:20:26 -03:00
|
|
|
// Constructor
|
2015-05-14 22:00:46 -03:00
|
|
|
AP_Motors::AP_Motors(uint16_t loop_rate, uint16_t speed_hz) :
|
2015-02-21 02:45:56 -04:00
|
|
|
_loop_rate(loop_rate),
|
2012-08-17 03:20:26 -03:00
|
|
|
_speed_hz(speed_hz),
|
2015-07-13 01:39:57 -03:00
|
|
|
_throttle_filter(),
|
2016-05-28 03:09:59 -03:00
|
|
|
_spool_desired(DESIRED_SHUT_DOWN),
|
2018-07-23 01:26:00 -03:00
|
|
|
_air_density_ratio(1.0f)
|
2012-04-02 05:26:37 -03:00
|
|
|
{
|
2018-03-21 21:45:52 -03:00
|
|
|
_instance = this;
|
2015-06-08 00:18:40 -03:00
|
|
|
|
2015-04-16 01:55:12 -03:00
|
|
|
// setup throttle filtering
|
2015-04-16 16:36:02 -03:00
|
|
|
_throttle_filter.set_cutoff_frequency(0.0f);
|
2015-04-01 00:16:43 -03:00
|
|
|
_throttle_filter.reset(0.0f);
|
2015-06-08 00:18:40 -03:00
|
|
|
|
|
|
|
// init limit flags
|
|
|
|
limit.roll_pitch = true;
|
|
|
|
limit.yaw = true;
|
|
|
|
limit.throttle_lower = true;
|
|
|
|
limit.throttle_upper = true;
|
2018-08-12 11:19:20 -03:00
|
|
|
_thrust_boost = false;
|
|
|
|
_thrust_balanced = true;
|
2012-04-02 05:26:37 -03:00
|
|
|
};
|
|
|
|
|
2013-08-08 10:15:04 -03:00
|
|
|
void AP_Motors::armed(bool arm)
|
|
|
|
{
|
2016-06-09 02:21:04 -03:00
|
|
|
if (_flags.armed != arm) {
|
|
|
|
_flags.armed = arm;
|
|
|
|
AP_Notify::flags.armed = arm;
|
2016-06-16 00:07:37 -03:00
|
|
|
if (!arm) {
|
|
|
|
save_params_on_disarm();
|
|
|
|
}
|
2016-06-09 02:21:04 -03:00
|
|
|
}
|
2015-07-13 01:39:57 -03:00
|
|
|
};
|
2016-01-04 01:56:54 -04:00
|
|
|
|
2016-02-03 07:55:55 -04:00
|
|
|
// pilot input in the -1 ~ +1 range for roll, pitch and yaw. 0~1 range for throttle
|
|
|
|
void AP_Motors::set_radio_passthrough(float roll_input, float pitch_input, float throttle_input, float yaw_input)
|
|
|
|
{
|
|
|
|
_roll_radio_passthrough = roll_input;
|
|
|
|
_pitch_radio_passthrough = pitch_input;
|
|
|
|
_throttle_radio_passthrough = throttle_input;
|
|
|
|
_yaw_radio_passthrough = yaw_input;
|
|
|
|
}
|
|
|
|
|
2016-01-04 01:56:54 -04:00
|
|
|
/*
|
|
|
|
write to an output channel
|
|
|
|
*/
|
|
|
|
void AP_Motors::rc_write(uint8_t chan, uint16_t pwm)
|
|
|
|
{
|
2017-10-23 00:16:13 -03:00
|
|
|
SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(chan);
|
2017-04-17 05:15:55 -03:00
|
|
|
SRV_Channels::set_output_pwm(function, pwm);
|
2016-01-04 01:56:54 -04:00
|
|
|
}
|
2016-01-04 06:24:06 -04:00
|
|
|
|
2018-05-20 22:37:38 -03:00
|
|
|
/*
|
|
|
|
write to an output channel for an angle actuator
|
|
|
|
*/
|
|
|
|
void AP_Motors::rc_write_angle(uint8_t chan, int16_t angle_cd)
|
|
|
|
{
|
|
|
|
SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(chan);
|
|
|
|
SRV_Channels::set_output_scaled(function, angle_cd);
|
|
|
|
}
|
|
|
|
|
2016-01-04 06:24:06 -04:00
|
|
|
/*
|
|
|
|
set frequency of a set of channels
|
|
|
|
*/
|
|
|
|
void AP_Motors::rc_set_freq(uint32_t mask, uint16_t freq_hz)
|
2016-01-04 16:35:24 -04:00
|
|
|
{
|
2016-04-22 00:24:04 -03:00
|
|
|
if (freq_hz > 50) {
|
|
|
|
_motor_fast_mask |= mask;
|
|
|
|
}
|
2018-03-14 03:04:20 -03:00
|
|
|
|
2017-04-17 05:15:55 -03:00
|
|
|
mask = rc_map_mask(mask);
|
2016-04-22 00:24:04 -03:00
|
|
|
hal.rcout->set_freq(mask, freq_hz);
|
2018-03-14 03:04:20 -03:00
|
|
|
|
|
|
|
switch (pwm_type(_pwm_type.get())) {
|
|
|
|
case PWM_TYPE_ONESHOT:
|
|
|
|
if (freq_hz > 50 && mask != 0) {
|
|
|
|
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT);
|
|
|
|
}
|
|
|
|
break;
|
2018-04-03 05:11:31 -03:00
|
|
|
case PWM_TYPE_ONESHOT125:
|
|
|
|
if (freq_hz > 50 && mask != 0) {
|
|
|
|
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT125);
|
|
|
|
}
|
|
|
|
break;
|
2018-03-14 03:04:20 -03:00
|
|
|
case PWM_TYPE_BRUSHED:
|
|
|
|
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_BRUSHED);
|
|
|
|
break;
|
|
|
|
case PWM_TYPE_DSHOT150:
|
|
|
|
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT150);
|
|
|
|
break;
|
|
|
|
case PWM_TYPE_DSHOT300:
|
|
|
|
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT300);
|
|
|
|
break;
|
|
|
|
case PWM_TYPE_DSHOT600:
|
|
|
|
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT600);
|
|
|
|
break;
|
|
|
|
case PWM_TYPE_DSHOT1200:
|
|
|
|
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT1200);
|
|
|
|
break;
|
|
|
|
default:
|
|
|
|
hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_NORMAL);
|
|
|
|
break;
|
2016-04-13 03:33:20 -03:00
|
|
|
}
|
2016-01-04 16:35:24 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
2017-04-17 05:15:55 -03:00
|
|
|
map an internal motor mask to real motor mask, accounting for
|
|
|
|
SERVOn_FUNCTION mappings, and allowing for multiple outputs per
|
|
|
|
motor number
|
2016-01-04 16:35:24 -04:00
|
|
|
*/
|
|
|
|
uint32_t AP_Motors::rc_map_mask(uint32_t mask) const
|
2016-01-04 06:24:06 -04:00
|
|
|
{
|
|
|
|
uint32_t mask2 = 0;
|
|
|
|
for (uint8_t i=0; i<32; i++) {
|
|
|
|
uint32_t bit = 1UL<<i;
|
|
|
|
if (mask & bit) {
|
2017-10-23 00:16:13 -03:00
|
|
|
SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(i);
|
2017-04-17 05:15:55 -03:00
|
|
|
mask2 |= SRV_Channels::get_output_channel_mask(function);
|
2016-01-04 06:24:06 -04:00
|
|
|
}
|
|
|
|
}
|
2016-01-04 16:35:24 -04:00
|
|
|
return mask2;
|
2016-01-04 06:24:06 -04:00
|
|
|
}
|
2016-02-02 08:22:53 -04:00
|
|
|
|
2016-04-21 04:32:25 -03:00
|
|
|
/*
|
2017-04-17 05:15:55 -03:00
|
|
|
add a motor, setting up default output function as needed
|
2016-04-21 04:32:25 -03:00
|
|
|
*/
|
|
|
|
void AP_Motors::add_motor_num(int8_t motor_num)
|
|
|
|
{
|
|
|
|
// ensure valid motor number is provided
|
|
|
|
if( motor_num >= 0 && motor_num < AP_MOTORS_MAX_NUM_MOTORS ) {
|
|
|
|
uint8_t chan;
|
2017-10-23 00:16:13 -03:00
|
|
|
SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(motor_num);
|
2017-01-03 05:56:57 -04:00
|
|
|
SRV_Channels::set_aux_channel_default(function, motor_num);
|
2017-04-17 05:15:55 -03:00
|
|
|
if (!SRV_Channels::find_channel(function, chan)) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_ERROR, "Motors: unable to setup motor %u", motor_num);
|
2016-04-21 04:32:25 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|