ardupilot/libraries/AP_Motors/AP_Motors_Class.cpp

199 lines
5.9 KiB
C++
Raw Normal View History

/*
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/>.
*/
/*
* AP_Motors.cpp - ArduCopter motors library
* Code by RandyMackay. DIYDrones.com
*
*/
2012-10-26 20:59:07 -03:00
#include "AP_Motors_Class.h"
#include <AP_HAL/AP_HAL.h>
2017-01-03 05:56:57 -04:00
#include <SRV_Channel/SRV_Channel.h>
#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;
// Constructor
AP_Motors::AP_Motors(uint16_t loop_rate, uint16_t speed_hz) :
2015-02-21 02:45:56 -04:00
_loop_rate(loop_rate),
_speed_hz(speed_hz),
_roll_in(0.0f),
_pitch_in(0.0f),
_yaw_in(0.0f),
_throttle_in(0.0f),
_throttle_avg_max(0.0f),
_throttle_filter(),
_spool_desired(DESIRED_SHUT_DOWN),
_batt_voltage(0.0f),
_batt_current(0.0f),
_air_density_ratio(1.0f),
_motor_fast_mask(0)
{
// init other flags
_flags.armed = false;
_flags.interlock = false;
_flags.initialised_ok = false;
// setup throttle filtering
2015-04-16 16:36:02 -03:00
_throttle_filter.set_cutoff_frequency(0.0f);
_throttle_filter.reset(0.0f);
// init limit flags
limit.roll_pitch = true;
limit.yaw = true;
limit.throttle_lower = true;
limit.throttle_upper = true;
};
2013-08-08 10:15:04 -03:00
void AP_Motors::armed(bool arm)
{
if (_flags.armed != arm) {
_flags.armed = arm;
AP_Notify::flags.armed = arm;
if (!arm) {
save_params_on_disarm();
}
}
};
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;
}
/*
write to an output channel
*/
void AP_Motors::rc_write(uint8_t chan, uint16_t pwm)
{
if (_pwm_type == PWM_TYPE_ONESHOT125 && (_motor_fast_mask & (1U<<chan))) {
// OneShot125 uses a PWM range from 125 to 250 usec
pwm /= 8;
/*
OneShot125 ESCs can be confused by pulses below 125 or above
250, making them fail the pulse type auto-detection. This
happens at least with BLHeli
*/
if (pwm < 125) {
pwm = 125;
} else if (pwm > 250) {
pwm = 250;
}
}
SRV_Channel::Aux_servo_function_t function = (SRV_Channel::Aux_servo_function_t)((uint8_t)SRV_Channel::k_motor1 + chan);
SRV_Channels::set_output_pwm(function, pwm);
}
/*
set frequency of a set of channels
*/
void AP_Motors::rc_set_freq(uint32_t mask, uint16_t freq_hz)
{
if (freq_hz > 50) {
_motor_fast_mask |= mask;
}
mask = rc_map_mask(mask);
hal.rcout->set_freq(mask, freq_hz);
if ((_pwm_type == PWM_TYPE_ONESHOT ||
_pwm_type == PWM_TYPE_ONESHOT125) &&
freq_hz > 50 &&
mask != 0) {
// tell HAL to do immediate output
hal.rcout->set_output_mode(AP_HAL::RCOutput::MODE_PWM_ONESHOT);
} else if (_pwm_type == PWM_TYPE_BRUSHED) {
hal.rcout->set_output_mode(AP_HAL::RCOutput::MODE_PWM_BRUSHED);
}
}
/*
map an internal motor mask to real motor mask, accounting for
SERVOn_FUNCTION mappings, and allowing for multiple outputs per
motor number
*/
uint32_t AP_Motors::rc_map_mask(uint32_t mask) const
{
uint32_t mask2 = 0;
for (uint8_t i=0; i<32; i++) {
uint32_t bit = 1UL<<i;
if (mask & bit) {
SRV_Channel::Aux_servo_function_t function = (SRV_Channel::Aux_servo_function_t)((uint8_t)SRV_Channel::k_motor1 + i);
mask2 |= SRV_Channels::get_output_channel_mask(function);
}
}
return mask2;
}
// convert input in -1 to +1 range to pwm output
2017-01-03 05:56:57 -04:00
int16_t AP_Motors::calc_pwm_output_1to1(float input, const SRV_Channel *servo)
{
int16_t ret;
input = constrain_float(input, -1.0f, 1.0f);
2017-01-03 05:56:57 -04:00
if (servo->get_reversed()) {
input = -input;
}
if (input >= 0.0f) {
2017-01-03 05:56:57 -04:00
ret = ((input * (servo->get_output_max() - servo->get_trim())) + servo->get_trim());
} else {
2017-01-03 05:56:57 -04:00
ret = ((input * (servo->get_trim() - servo->get_output_min())) + servo->get_trim());
}
2017-01-03 05:56:57 -04:00
return constrain_int16(ret, servo->get_output_min(), servo->get_output_max());
}
// convert input in 0 to +1 range to pwm output
2017-01-03 05:56:57 -04:00
int16_t AP_Motors::calc_pwm_output_0to1(float input, const SRV_Channel *servo)
{
int16_t ret;
input = constrain_float(input, 0.0f, 1.0f);
2017-01-03 05:56:57 -04:00
if (servo->get_reversed()) {
input = 1.0f-input;
}
2017-01-03 05:56:57 -04:00
ret = input * (servo->get_output_max() - servo->get_output_min()) + servo->get_output_min();
2017-01-03 05:56:57 -04:00
return constrain_int16(ret, servo->get_output_min(), servo->get_output_max());
}
/*
add a motor, setting up default output function as needed
*/
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;
SRV_Channel::Aux_servo_function_t function;
if (motor_num < 8) {
function = (SRV_Channel::Aux_servo_function_t)(SRV_Channel::k_motor1+motor_num);
} else {
function = (SRV_Channel::Aux_servo_function_t)(SRV_Channel::k_motor9+(motor_num-8));
}
2017-01-03 05:56:57 -04:00
SRV_Channels::set_aux_channel_default(function, motor_num);
if (!SRV_Channels::find_channel(function, chan)) {
gcs().send_text(MAV_SEVERITY_ERROR, "Motors: unable to setup motor %u", motor_num);
}
}
}