mirror of https://github.com/ArduPilot/ardupilot
Sub: Clean up radio.cpp
This commit is contained in:
parent
1d3d6c064e
commit
4349eaba32
|
@ -672,7 +672,6 @@ private:
|
||||||
float pv_get_bearing_cd(const Vector3f &origin, const Vector3f &destination);
|
float pv_get_bearing_cd(const Vector3f &origin, const Vector3f &destination);
|
||||||
float pv_get_horizontal_distance_cm(const Vector3f &origin, const Vector3f &destination);
|
float pv_get_horizontal_distance_cm(const Vector3f &origin, const Vector3f &destination);
|
||||||
float pv_distance_to_home_cm(const Vector3f &destination);
|
float pv_distance_to_home_cm(const Vector3f &destination);
|
||||||
void default_dead_zones();
|
|
||||||
void init_rc_in();
|
void init_rc_in();
|
||||||
void init_rc_out();
|
void init_rc_out();
|
||||||
void enable_motor_output();
|
void enable_motor_output();
|
||||||
|
|
|
@ -1,5 +1,13 @@
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
|
// enable_motor_output() - enable and output lowest possible value to motors
|
||||||
|
void Sub::enable_motor_output()
|
||||||
|
{
|
||||||
|
// enable motors
|
||||||
|
motors.enable();
|
||||||
|
motors.output_min();
|
||||||
|
}
|
||||||
|
|
||||||
// init_arm_motors - performs arming process including initialisation of barometer and gyros
|
// init_arm_motors - performs arming process including initialisation of barometer and gyros
|
||||||
// returns false if arming failed because of pre-arm checks, arming checks or a gyro calibration failure
|
// returns false if arming failed because of pre-arm checks, arming checks or a gyro calibration failure
|
||||||
bool Sub::init_arm_motors(bool arming_from_gcs)
|
bool Sub::init_arm_motors(bool arming_from_gcs)
|
||||||
|
|
|
@ -1,19 +1,5 @@
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
|
|
||||||
// Function that will read the radio data, limit servos and trigger a failsafe
|
|
||||||
// ----------------------------------------------------------------------------
|
|
||||||
|
|
||||||
void Sub::default_dead_zones()
|
|
||||||
{
|
|
||||||
channel_roll->set_default_dead_zone(30);
|
|
||||||
channel_pitch->set_default_dead_zone(30);
|
|
||||||
channel_throttle->set_default_dead_zone(30);
|
|
||||||
channel_yaw->set_default_dead_zone(40);
|
|
||||||
channel_forward->set_default_dead_zone(30);
|
|
||||||
channel_lateral->set_default_dead_zone(30);
|
|
||||||
}
|
|
||||||
|
|
||||||
void Sub::init_rc_in()
|
void Sub::init_rc_in()
|
||||||
{
|
{
|
||||||
channel_pitch = RC_Channels::rc_channel(0);
|
channel_pitch = RC_Channels::rc_channel(0);
|
||||||
|
@ -31,18 +17,13 @@ void Sub::init_rc_in()
|
||||||
channel_forward->set_angle(ROLL_PITCH_INPUT_MAX);
|
channel_forward->set_angle(ROLL_PITCH_INPUT_MAX);
|
||||||
channel_lateral->set_angle(ROLL_PITCH_INPUT_MAX);
|
channel_lateral->set_angle(ROLL_PITCH_INPUT_MAX);
|
||||||
|
|
||||||
// force throttle trim to 1100
|
|
||||||
channel_throttle->set_radio_trim(1100);
|
|
||||||
channel_throttle->save_eeprom();
|
|
||||||
|
|
||||||
//set auxiliary servo ranges
|
|
||||||
// g.rc_5.set_range(0,1000);
|
|
||||||
// g.rc_6.set_range(0,1000);
|
|
||||||
// g.rc_7.set_range(0,1000);
|
|
||||||
// g.rc_8.set_range(0,1000);
|
|
||||||
|
|
||||||
// set default dead zones
|
// set default dead zones
|
||||||
default_dead_zones();
|
channel_roll->set_default_dead_zone(30);
|
||||||
|
channel_pitch->set_default_dead_zone(30);
|
||||||
|
channel_throttle->set_default_dead_zone(30);
|
||||||
|
channel_yaw->set_default_dead_zone(40);
|
||||||
|
channel_forward->set_default_dead_zone(30);
|
||||||
|
channel_lateral->set_default_dead_zone(30);
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
||||||
// initialize rc input to 1500 on control channels (rather than 0)
|
// initialize rc input to 1500 on control channels (rather than 0)
|
||||||
|
@ -68,11 +49,3 @@ void Sub::init_rc_out()
|
||||||
// refresh auxiliary channel to function map
|
// refresh auxiliary channel to function map
|
||||||
SRV_Channels::update_aux_servo_function();
|
SRV_Channels::update_aux_servo_function();
|
||||||
}
|
}
|
||||||
|
|
||||||
// enable_motor_output() - enable and output lowest possible value to motors
|
|
||||||
void Sub::enable_motor_output()
|
|
||||||
{
|
|
||||||
// enable motors
|
|
||||||
motors.enable();
|
|
||||||
motors.output_min();
|
|
||||||
}
|
|
||||||
|
|
Loading…
Reference in New Issue