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-02-21 02:45:56 -04:00
|
|
|
_loop_rate(loop_rate),
|
2012-08-17 03:20:26 -03:00
|
|
|
_speed_hz(speed_hz),
|
2016-01-21 22:08:55 -04:00
|
|
|
_roll_in(0.0f),
|
|
|
|
_pitch_in(0.0f),
|
|
|
|
_yaw_in(0.0f),
|
2015-07-13 01:39:57 -03:00
|
|
|
_throttle_in(0.0f),
|
2016-06-08 05:48:54 -03:00
|
|
|
_throttle_avg_max(0.0f),
|
2015-07-13 01:39:57 -03:00
|
|
|
_throttle_filter(),
|
2016-05-28 03:09:59 -03:00
|
|
|
_spool_desired(DESIRED_SHUT_DOWN),
|
2015-02-23 02:35:10 -04:00
|
|
|
_batt_voltage(0.0f),
|
|
|
|
_batt_current(0.0f),
|
2016-01-20 05:06:16 -04:00
|
|
|
_air_density_ratio(1.0f),
|
2016-05-28 03:09:59 -03:00
|
|
|
_motor_map_mask(0),
|
|
|
|
_motor_fast_mask(0)
|
2012-04-02 05:26:37 -03:00
|
|
|
{
|
2015-06-08 00:18:40 -03:00
|
|
|
// init other flags
|
|
|
|
_flags.armed = 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)
|
|
|
|
{
|
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)
|
|
|
|
{
|
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-04-22 00:24:04 -03:00
|
|
|
if (_pwm_type == PWM_TYPE_ONESHOT125 && (_motor_fast_mask & (1U<<chan))) {
|
2016-04-13 03:33:20 -03:00
|
|
|
// OneShot125 uses a PWM range from 125 to 250 usec
|
|
|
|
pwm /= 8;
|
2016-04-16 05:52:12 -03:00
|
|
|
/*
|
|
|
|
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;
|
|
|
|
}
|
2016-04-13 03:33:20 -03:00
|
|
|
}
|
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
|
|
|
{
|
2016-04-22 00:24:04 -03:00
|
|
|
mask = rc_map_mask(mask);
|
|
|
|
if (freq_hz > 50) {
|
|
|
|
_motor_fast_mask |= mask;
|
|
|
|
}
|
|
|
|
hal.rcout->set_freq(mask, freq_hz);
|
|
|
|
if ((_pwm_type == PWM_TYPE_ONESHOT ||
|
|
|
|
_pwm_type == PWM_TYPE_ONESHOT125) &&
|
2016-05-25 23:18:03 -03:00
|
|
|
freq_hz > 50 &&
|
|
|
|
mask != 0) {
|
2016-04-13 03:33:20 -03:00
|
|
|
// tell HAL to do immediate output
|
|
|
|
hal.rcout->set_output_mode(AP_HAL::RCOutput::MODE_PWM_ONESHOT);
|
|
|
|
}
|
2016-01-04 16:35:24 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
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) {
|
2016-04-22 22:22:01 -03:00
|
|
|
if ((i < AP_MOTORS_MAX_NUM_MOTORS) && (_motor_map_mask & bit)) {
|
2016-01-04 06:24:06 -04:00
|
|
|
// 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
|
|
|
}
|
2016-02-02 08:22:53 -04:00
|
|
|
|
|
|
|
// convert input in -1 to +1 range to pwm output
|
|
|
|
int16_t AP_Motors::calc_pwm_output_1to1(float input, const RC_Channel& servo)
|
|
|
|
{
|
|
|
|
int16_t ret;
|
|
|
|
|
|
|
|
input = constrain_float(input, -1.0f, 1.0f);
|
|
|
|
|
|
|
|
if (servo.get_reverse()) {
|
|
|
|
input = -input;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (input >= 0.0f) {
|
AP_Motors: Fix up after RC_Channels refactor
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:28:21 -03:00
|
|
|
ret = ((input * (servo.get_radio_max() - servo.get_radio_trim())) + servo.get_radio_trim());
|
2016-02-02 08:22:53 -04:00
|
|
|
} else {
|
AP_Motors: Fix up after RC_Channels refactor
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:28:21 -03:00
|
|
|
ret = ((input * (servo.get_radio_trim() - servo.get_radio_min())) + servo.get_radio_trim());
|
2016-02-02 08:22:53 -04:00
|
|
|
}
|
|
|
|
|
AP_Motors: Fix up after RC_Channels refactor
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:28:21 -03:00
|
|
|
return constrain_int16(ret, servo.get_radio_min(), servo.get_radio_max());
|
2016-02-02 08:22:53 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// convert input in 0 to +1 range to pwm output
|
|
|
|
int16_t AP_Motors::calc_pwm_output_0to1(float input, const RC_Channel& servo)
|
|
|
|
{
|
|
|
|
int16_t ret;
|
|
|
|
|
|
|
|
input = constrain_float(input, 0.0f, 1.0f);
|
|
|
|
|
|
|
|
if (servo.get_reverse()) {
|
|
|
|
input = 1.0f-input;
|
|
|
|
}
|
|
|
|
|
AP_Motors: Fix up after RC_Channels refactor
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:28:21 -03:00
|
|
|
ret = input * (servo.get_radio_max() - servo.get_radio_min()) + servo.get_radio_min();
|
2016-02-02 08:22:53 -04:00
|
|
|
|
AP_Motors: Fix up after RC_Channels refactor
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:28:21 -03:00
|
|
|
return constrain_int16(ret, servo.get_radio_min(), servo.get_radio_max());
|
2016-02-02 08:22:53 -04:00
|
|
|
}
|
2016-04-21 04:32:25 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
add a motor, setting up _motor_map and _motor_map_mask 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;
|
|
|
|
if (RC_Channel_aux::find_channel((RC_Channel_aux::Aux_servo_function_t)(RC_Channel_aux::k_motor1+motor_num),
|
|
|
|
chan)) {
|
|
|
|
_motor_map[motor_num] = chan;
|
|
|
|
_motor_map_mask |= 1U<<motor_num;
|
|
|
|
} else {
|
|
|
|
// disable this channel from being used by RC_Channel_aux
|
|
|
|
RC_Channel_aux::disable_aux_channel(motor_num);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|