2014-01-20 00:36:09 -04: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/>.
|
|
|
|
*/
|
|
|
|
/*
|
|
|
|
* AP_ServoRelayEvents - handle servo and relay MAVLink events
|
|
|
|
*/
|
|
|
|
|
|
|
|
|
2015-08-11 03:28:45 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include "AP_ServoRelayEvents.h"
|
|
|
|
#include <RC_Channel/RC_Channel.h>
|
2014-01-20 00:36:09 -04:00
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2014-02-05 19:03:26 -04:00
|
|
|
bool AP_ServoRelayEvents::do_set_servo(uint8_t _channel, uint16_t pwm)
|
2014-01-20 00:36:09 -04:00
|
|
|
{
|
2014-02-05 19:03:26 -04:00
|
|
|
if (!(mask & 1U<<(_channel-1))) {
|
2014-01-20 00:36:09 -04:00
|
|
|
// not allowed
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if (type == EVENT_TYPE_SERVO &&
|
2014-02-05 19:03:26 -04:00
|
|
|
channel == _channel) {
|
2014-01-20 00:36:09 -04:00
|
|
|
// cancel previous repeat
|
|
|
|
repeat = 0;
|
|
|
|
}
|
2014-02-05 19:03:26 -04:00
|
|
|
hal.rcout->enable_ch(_channel-1);
|
|
|
|
hal.rcout->write(_channel-1, pwm);
|
2014-01-20 00:36:09 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool AP_ServoRelayEvents::do_set_relay(uint8_t relay_num, uint8_t state)
|
|
|
|
{
|
|
|
|
if (!relay.enabled(relay_num)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if (type == EVENT_TYPE_RELAY &&
|
|
|
|
channel == relay_num) {
|
|
|
|
// cancel previous repeat
|
|
|
|
repeat = 0;
|
|
|
|
}
|
|
|
|
if (state == 1) {
|
|
|
|
relay.on(relay_num);
|
|
|
|
} else if (state == 0) {
|
|
|
|
relay.off(relay_num);
|
|
|
|
} else {
|
|
|
|
relay.toggle(relay_num);
|
|
|
|
}
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool AP_ServoRelayEvents::do_repeat_servo(uint8_t _channel, uint16_t _servo_value,
|
|
|
|
int16_t _repeat, uint16_t _delay_ms)
|
|
|
|
{
|
|
|
|
if (!(mask & 1U<<(_channel-1))) {
|
|
|
|
// not allowed
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
channel = _channel;
|
|
|
|
type = EVENT_TYPE_SERVO;
|
|
|
|
|
|
|
|
start_time_ms = 0;
|
|
|
|
delay_ms = _delay_ms / 2;
|
|
|
|
repeat = _repeat * 2;
|
|
|
|
servo_value = _servo_value;
|
|
|
|
update_events();
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool AP_ServoRelayEvents::do_repeat_relay(uint8_t relay_num, int16_t _repeat, uint32_t _delay_ms)
|
|
|
|
{
|
|
|
|
if (!relay.enabled(relay_num)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
type = EVENT_TYPE_RELAY;
|
|
|
|
channel = relay_num;
|
|
|
|
start_time_ms = 0;
|
|
|
|
delay_ms = _delay_ms/2; // half cycle time
|
|
|
|
repeat = _repeat*2; // number of full cycles
|
|
|
|
update_events();
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
update state for MAV_CMD_DO_REPEAT_SERVO and MAV_CMD_DO_REPEAT_RELAY
|
|
|
|
*/
|
|
|
|
void AP_ServoRelayEvents::update_events(void)
|
|
|
|
{
|
2015-11-19 23:14:42 -04:00
|
|
|
if (repeat == 0 || (AP_HAL::millis() - start_time_ms) < delay_ms) {
|
2014-01-20 00:36:09 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2015-11-19 23:14:42 -04:00
|
|
|
start_time_ms = AP_HAL::millis();
|
2014-01-20 00:36:09 -04:00
|
|
|
|
|
|
|
switch (type) {
|
|
|
|
case EVENT_TYPE_SERVO:
|
|
|
|
hal.rcout->enable_ch(channel-1);
|
|
|
|
if (repeat & 1) {
|
AP_ServoRelayEvents: 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:31:03 -03:00
|
|
|
hal.rcout->write(channel-1, RC_Channel::rc_channel(channel-1)->get_radio_trim());
|
2014-01-20 00:36:09 -04:00
|
|
|
} else {
|
|
|
|
hal.rcout->write(channel-1, servo_value);
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
|
|
|
case EVENT_TYPE_RELAY:
|
|
|
|
relay.toggle(channel);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (repeat > 0) {
|
|
|
|
repeat--;
|
|
|
|
} else {
|
|
|
|
// toggle bottom bit so servos flip in value
|
|
|
|
repeat ^= 1;
|
|
|
|
}
|
|
|
|
}
|