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/ArduSub/radio.cpp
Views: 1798
#include "Sub.h"12void Sub::init_rc_in()3{4channel_pitch = RC_Channels::rc_channel(0);5channel_roll = RC_Channels::rc_channel(1);6channel_throttle = RC_Channels::rc_channel(2);7channel_yaw = RC_Channels::rc_channel(3);8channel_forward = RC_Channels::rc_channel(4);9channel_lateral = RC_Channels::rc_channel(5);1011// set rc channel ranges12channel_roll->set_angle(ROLL_PITCH_INPUT_MAX);13channel_pitch->set_angle(ROLL_PITCH_INPUT_MAX);14channel_yaw->set_angle(ROLL_PITCH_INPUT_MAX);15channel_throttle->set_range(1000);16channel_forward->set_angle(ROLL_PITCH_INPUT_MAX);17channel_lateral->set_angle(ROLL_PITCH_INPUT_MAX);1819// set default dead zones20channel_roll->set_default_dead_zone(30);21channel_pitch->set_default_dead_zone(30);22channel_throttle->set_default_dead_zone(30);23channel_yaw->set_default_dead_zone(40);24channel_forward->set_default_dead_zone(30);25channel_lateral->set_default_dead_zone(30);2627#if CONFIG_HAL_BOARD != HAL_BOARD_SITL28// initialize rc input to 1500 on control channels (rather than 0)29for (int i = 0; i < 6; i++) {30RC_Channels::set_override(i, 1500);31}3233RC_Channels::set_override(6, 1500); // camera pan channel34RC_Channels::set_override(7, 1500); // camera tilt channel3536RC_Channel* chan = RC_Channels::rc_channel(8);37uint16_t min = chan->get_radio_min();38RC_Channels::set_override(8, min); // lights 1 channel3940chan = RC_Channels::rc_channel(9);41min = chan->get_radio_min();42RC_Channels::set_override(9, min); // lights 2 channel4344RC_Channels::set_override(10, 1100); // video switch45#endif46}4748// init_rc_out -- initialise motors and check if pilot wants to perform ESC calibration49void Sub::init_rc_out()50{51motors.set_update_rate(g.rc_speed);52motors.init((AP_Motors::motor_frame_class)g.frame_configuration.get(), AP_Motors::motor_frame_type::MOTOR_FRAME_TYPE_PLUS);53motors.convert_pwm_min_max_param(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());54motors.update_throttle_range();5556// enable output to motors57if (arming.rc_calibration_checks(true)) {58enable_motor_output();59}6061// refresh auxiliary channel to function map62SRV_Channels::update_aux_servo_function();63}646566