ardupilot/APMrover2/control_modes.cpp

178 lines
5.1 KiB
C++
Raw Normal View History

2015-05-13 00:16:45 -03:00
#include "Rover.h"
static const int16_t CH_7_PWM_TRIGGER = 1800;
2017-07-18 23:19:08 -03:00
Mode *Rover::control_mode_from_num(const enum mode num)
{
Mode *ret = nullptr;
switch (num) {
case MANUAL:
ret = &mode_manual;
break;
case LEARNING:
ret = &mode_learning;
break;
case STEERING:
ret = &mode_steering;
break;
case HOLD:
ret = &mode_hold;
break;
case AUTO:
ret = &mode_auto;
break;
case RTL:
ret = &mode_rtl;
break;
case GUIDED:
ret = &mode_guided;
break;
case INITIALISING:
ret = &mode_initializing;
break;
default:
break;
}
return ret;
}
void Rover::read_control_switch()
{
static bool switch_debouncer;
2017-01-31 06:12:26 -04:00
const uint8_t switchPosition = readSwitch();
// If switchPosition = 255 this indicates that the mode control channel input was out of range
// If we get this value we do not want to change modes.
if (switchPosition == 255) {
return;
}
if (AP_HAL::millis() - failsafe.last_valid_rc_ms > 100) {
// only use signals that are less than 0.1s old.
return;
}
// we look for changes in the switch position. If the
// RST_SWITCH_CH parameter is set, then it is a switch that can be
// used to force re-reading of the control switch. This is useful
// when returning to the previous mode after a failsafe or fence
// breach. This channel is best used on a momentary switch (such
// as a spring loaded trainer switch).
if (oldSwitchPosition != switchPosition ||
(g.reset_switch_chan != 0 &&
hal.rcin->read(g.reset_switch_chan-1) > RESET_SWITCH_CHAN_PWM)) {
if (switch_debouncer == false) {
// this ensures that mode switches only happen if the
// switch changes for 2 reads. This prevents momentary
// spikes in the mode control channel from causing a mode
// switch
switch_debouncer = true;
return;
}
2017-07-18 23:19:08 -03:00
Mode *new_mode = control_mode_from_num((enum mode)modes[switchPosition].get());
if (new_mode != nullptr) {
2017-07-24 14:05:59 -03:00
set_mode(*new_mode, MODE_REASON_TX_COMMAND);
2017-07-18 23:19:08 -03:00
}
oldSwitchPosition = switchPosition;
prev_WP = current_loc;
// reset speed integrator
g.pidSpeedThrottle.reset_I();
}
switch_debouncer = false;
}
uint8_t Rover::readSwitch(void) {
2017-01-31 06:12:26 -04:00
const uint16_t pulsewidth = hal.rcin->read(g.mode_channel - 1);
if (pulsewidth <= 900 || pulsewidth >= 2200) {
return 255; // This is an error condition
}
if (pulsewidth <= 1230) {
return 0;
}
if (pulsewidth <= 1360) {
return 1;
}
if (pulsewidth <= 1490) {
return 2;
}
if (pulsewidth <= 1620) {
return 3;
}
if (pulsewidth <= 1749) {
return 4; // Software Manual
}
return 5; // Hardware Manual
}
void Rover::reset_control_switch()
{
oldSwitchPosition = 254;
read_control_switch();
}
// read at 10 hz
// set this to your trainer switch
void Rover::read_trim_switch()
{
switch ((enum ch7_option)g.ch7_option.get()) {
case CH7_DO_NOTHING:
break;
case CH7_SAVE_WP:
if (channel_learn->get_radio_in() > CH_7_PWM_TRIGGER) {
// switch is engaged
ch7_flag = true;
} else { // switch is disengaged
if (ch7_flag) {
ch7_flag = false;
2017-07-18 23:19:08 -03:00
if (control_mode == &mode_manual) {
hal.console->printf("Erasing waypoints\n");
// if SW7 is ON in MANUAL = Erase the Flight Plan
mission.clear();
APMRover2: Fix up after refactoring RC_Channel class 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:49:39 -03:00
if (channel_steer->get_control_in() > 3000) {
// if roll is full right store the current location as home
2017-06-05 04:55:24 -03:00
set_home_to_current_location(false);
}
2017-07-18 23:19:08 -03:00
} else if (control_mode == &mode_learning || control_mode == &mode_steering) {
// if SW7 is ON in LEARNING = record the Wp
// create new mission command
AP_Mission::Mission_Command cmd = {};
// set new waypoint to current location
cmd.content.location = current_loc;
// make the new command to a waypoint
cmd.id = MAV_CMD_NAV_WAYPOINT;
// save command
if (mission.add_cmd(cmd)) {
2017-03-30 11:07:24 -03:00
hal.console->printf("Learning waypoint %u", static_cast<uint32_t>(mission.num_commands()));
}
2017-07-18 23:19:08 -03:00
} else if (control_mode == &mode_auto) {
// if SW7 is ON in AUTO = set to RTL
2017-07-24 14:05:59 -03:00
set_mode(mode_rtl, MODE_REASON_TX_COMMAND);
break;
}
}
}
break;
}
}
bool Rover::motor_active()
{
// Check if armed and output throttle servo is not neutral
if (hal.util->get_soft_armed()) {
if (!is_zero(g2.motors.get_throttle())) {
return true;
}
}
return false;
}