2013-05-29 20:51:34 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
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>
|
2012-10-26 20:59:07 -03:00
|
|
|
extern const AP_HAL::HAL& hal;
|
2012-04-02 05:26:37 -03:00
|
|
|
|
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-05-25 08:17:35 -03:00
|
|
|
_roll_control_input(0.0f),
|
|
|
|
_pitch_control_input(0.0f),
|
|
|
|
_throttle_control_input(0.0f),
|
|
|
|
_yaw_control_input(0.0f),
|
|
|
|
_throttle_pwm_scalar(1.0f),
|
2015-08-03 01:36:10 -03:00
|
|
|
_rpy_pwm_scalar(0.074f),
|
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-05-25 08:17:35 -03:00
|
|
|
_throttle_radio_min(1100),
|
|
|
|
_throttle_radio_max(1900),
|
2015-07-13 01:39:57 -03:00
|
|
|
_throttle_in(0.0f),
|
|
|
|
_throttle_filter(),
|
2015-02-23 02:35:10 -04:00
|
|
|
_batt_voltage(0.0f),
|
|
|
|
_batt_current(0.0f),
|
2015-07-13 01:39:57 -03:00
|
|
|
_air_density_ratio(1.0f)
|
2012-04-02 05:26:37 -03:00
|
|
|
{
|
2015-06-08 00:18:40 -03:00
|
|
|
// init other flags
|
|
|
|
_flags.armed = false;
|
|
|
|
_flags.stabilizing = false;
|
|
|
|
_flags.frame_orientation = AP_MOTORS_X_FRAME;
|
|
|
|
_flags.interlock = false;
|
|
|
|
|
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;
|
2012-04-02 05:26:37 -03:00
|
|
|
};
|
|
|
|
|
2013-08-08 10:15:04 -03:00
|
|
|
void AP_Motors::armed(bool arm)
|
|
|
|
{
|
2013-09-12 10:27:44 -03:00
|
|
|
_flags.armed = arm;
|
|
|
|
AP_Notify::flags.armed = arm;
|
2015-07-13 01:39:57 -03:00
|
|
|
};
|
2016-01-04 01:56:54 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
write to an output channel
|
|
|
|
*/
|
|
|
|
void AP_Motors::rc_write(uint8_t chan, uint16_t pwm)
|
|
|
|
{
|
2016-01-04 02:48:55 -04:00
|
|
|
if (_motor_map_mask & (1U<<chan)) {
|
|
|
|
// we have a mapped motor number for this channel
|
|
|
|
chan = _motor_map[chan];
|
|
|
|
}
|
2016-01-04 01:56:54 -04:00
|
|
|
hal.rcout->write(chan, pwm);
|
|
|
|
}
|
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
|
|
|
{
|
|
|
|
hal.rcout->set_freq(rc_map_mask(mask), freq_hz);
|
|
|
|
}
|
|
|
|
|
|
|
|
void AP_Motors::rc_enable_ch(uint8_t chan)
|
|
|
|
{
|
|
|
|
if (_motor_map_mask & (1U<<chan)) {
|
|
|
|
// we have a mapped motor number for this channel
|
|
|
|
chan = _motor_map[chan];
|
|
|
|
}
|
|
|
|
hal.rcout->enable_ch(chan);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
map an internal motor mask to real motor mask
|
|
|
|
*/
|
|
|
|
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) {
|
|
|
|
if (_motor_map_mask & bit) {
|
|
|
|
// we have a mapped motor number for this channel
|
|
|
|
mask2 |= (1UL << _motor_map[i]);
|
|
|
|
} else {
|
|
|
|
mask2 |= bit;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2016-01-04 16:35:24 -04:00
|
|
|
return mask2;
|
2016-01-04 06:24:06 -04:00
|
|
|
}
|