Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Rover/radio.cpp
Views: 1798
#include "Rover.h"12/*3allow for runtime change of control channel ordering4*/5void Rover::set_control_channels(void)6{7// check change on RCMAP8// the library gaurantees that these are non-nullptr:9channel_steer = &rc().get_roll_channel();10channel_throttle = &rc().get_throttle_channel();11channel_lateral = &rc().get_yaw_channel();1213// set rc channel ranges14channel_steer->set_angle(SERVO_MAX);15channel_throttle->set_angle(100);16if (channel_lateral != nullptr) {17channel_lateral->set_angle(100);18}1920// walking robots rc input init21channel_roll = rc().find_channel_for_option(RC_Channel::AUX_FUNC::ROLL);22channel_pitch = rc().find_channel_for_option(RC_Channel::AUX_FUNC::PITCH);23channel_walking_height = rc().find_channel_for_option(RC_Channel::AUX_FUNC::WALKING_HEIGHT);24if (channel_roll != nullptr) {25channel_roll->set_angle(SERVO_MAX);26channel_roll->set_default_dead_zone(30);27}28if (channel_pitch != nullptr) {29channel_pitch->set_angle(SERVO_MAX);30channel_pitch->set_default_dead_zone(30);31}32if (channel_walking_height != nullptr) {33channel_walking_height->set_angle(SERVO_MAX);34channel_walking_height->set_default_dead_zone(30);35}3637// sailboat rc input init38g2.sailboat.init_rc_in();3940// Allow to reconfigure output when not armed41if (!arming.is_armed()) {42g2.motors.setup_servo_output();43// For a rover safety is TRIM throttle44g2.motors.setup_safety_output();45}46// setup correct scaling for ESCs like the UAVCAN ESCs which47// take a proportion of speed. Default to 1000 to 2000 for systems without48// a k_throttle output49hal.rcout->set_esc_scaling(1000, 2000);50g2.servo_channels.set_esc_scaling_for(SRV_Channel::k_throttle);51}5253void Rover::init_rc_in()54{55// set rc dead zones56channel_steer->set_default_dead_zone(30);57channel_throttle->set_default_dead_zone(30);58if (channel_lateral != nullptr) {59channel_lateral->set_default_dead_zone(30);60}61}6263/*64check for driver input on rudder/steering stick for arming/disarming65*/66void Rover::rudder_arm_disarm_check()67{68// check if arming/disarm using rudder is allowed69const AP_Arming::RudderArming arming_rudder = arming.get_rudder_arming_type();70if (arming_rudder == AP_Arming::RudderArming::IS_DISABLED) {71return;72}7374// In Rover we need to check that its set to the throttle trim and within the DZ75// if throttle is not within trim dz, then pilot cannot rudder arm/disarm76if (!channel_throttle->in_trim_dz()) {77rudder_arm_timer = 0;78return;79}8081// check if arming/disarming allowed from this mode82if (!control_mode->allows_arming_from_transmitter()) {83rudder_arm_timer = 0;84return;85}8687if (!arming.is_armed()) {88// when not armed, full right rudder starts arming counter89if (channel_steer->get_control_in() > 4000) {90const uint32_t now = millis();9192if (rudder_arm_timer == 0 ||93now - rudder_arm_timer < ARM_DELAY_MS) {94if (rudder_arm_timer == 0) {95rudder_arm_timer = now;96}97} else {98// time to arm!99arming.arm(AP_Arming::Method::RUDDER);100rudder_arm_timer = 0;101}102} else {103// not at full right rudder104rudder_arm_timer = 0;105}106} else if ((arming_rudder == AP_Arming::RudderArming::ARMDISARM) && !g2.motors.active()) {107// when armed and motor not active (not moving), full left rudder starts disarming counter108if (channel_steer->get_control_in() < -4000) {109const uint32_t now = millis();110111if (rudder_arm_timer == 0 ||112now - rudder_arm_timer < ARM_DELAY_MS) {113if (rudder_arm_timer == 0) {114rudder_arm_timer = now;115}116} else {117// time to disarm!118arming.disarm(AP_Arming::Method::RUDDER);119rudder_arm_timer = 0;120}121} else {122// not at full left rudder123rudder_arm_timer = 0;124}125}126}127128void Rover::read_radio()129{130if (!rc().read_input()) {131// check if we lost RC link132radio_failsafe_check(channel_throttle->get_radio_in());133return;134}135136failsafe.last_valid_rc_ms = AP_HAL::millis();137// check that RC value are valid138radio_failsafe_check(channel_throttle->get_radio_in());139140// check if we try to do RC arm/disarm141rudder_arm_disarm_check();142}143144void Rover::radio_failsafe_check(uint16_t pwm)145{146if (!g.fs_throttle_enabled) {147// radio failsafe disabled148return;149}150151bool failed = pwm < static_cast<uint16_t>(g.fs_throttle_value);152if (AP_HAL::millis() - failsafe.last_valid_rc_ms > 500) {153failed = true;154}155AP_Notify::flags.failsafe_radio = failed;156failsafe_trigger(FAILSAFE_EVENT_THROTTLE, "Radio", failed);157}158159160