mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
ACM : Toy mode updates
This commit is contained in:
parent
1e0ab8768e
commit
8160aa6103
@ -2,8 +2,7 @@
|
|||||||
// Toy Mode - THOR
|
// Toy Mode - THOR
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
static boolean CH7_toy_flag;
|
static boolean CH7_toy_flag;
|
||||||
static boolean CH6_toy_flag;
|
//static boolean CH6_toy_flag;
|
||||||
static int16_t saved_toy_throttle;
|
|
||||||
|
|
||||||
#if TOY_MIXER == TOY_LOOKUP_TABLE
|
#if TOY_MIXER == TOY_LOOKUP_TABLE
|
||||||
static const int16_t toy_lookup[] = {
|
static const int16_t toy_lookup[] = {
|
||||||
@ -21,6 +20,8 @@ static const int16_t toy_lookup[] = {
|
|||||||
//called at 10hz
|
//called at 10hz
|
||||||
void update_toy_throttle()
|
void update_toy_throttle()
|
||||||
{
|
{
|
||||||
|
/*
|
||||||
|
// Disabled, now handled by TOY_A (Alt hold) and TOY_M (Manual throttle)
|
||||||
if (false == CH6_toy_flag && g.rc_6.radio_in >= CH_6_PWM_TRIGGER){
|
if (false == CH6_toy_flag && g.rc_6.radio_in >= CH_6_PWM_TRIGGER){
|
||||||
CH6_toy_flag = true;
|
CH6_toy_flag = true;
|
||||||
throttle_mode = THROTTLE_MANUAL;
|
throttle_mode = THROTTLE_MANUAL;
|
||||||
@ -30,13 +31,14 @@ void update_toy_throttle()
|
|||||||
throttle_mode = THROTTLE_AUTO;
|
throttle_mode = THROTTLE_AUTO;
|
||||||
set_new_altitude(current_loc.alt);
|
set_new_altitude(current_loc.alt);
|
||||||
saved_toy_throttle = g.rc_3.control_in;
|
saved_toy_throttle = g.rc_3.control_in;
|
||||||
}
|
}*/
|
||||||
|
|
||||||
// look for a change in throttle position to exit throttle hold
|
// look for a change in throttle position to exit throttle hold
|
||||||
if(abs(g.rc_3.control_in - saved_toy_throttle) > 40){
|
if(abs(g.rc_3.control_in - saved_toy_throttle) > 40){
|
||||||
throttle_mode = THROTTLE_MANUAL;
|
throttle_mode = THROTTLE_MANUAL;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#define TOY_ALT_SMALL 25
|
#define TOY_ALT_SMALL 25
|
||||||
#define TOY_ALT_LARGE 100
|
#define TOY_ALT_LARGE 100
|
||||||
|
|
||||||
@ -165,7 +167,7 @@ void roll_pitch_toy()
|
|||||||
#if TOY_EDF == ENABLED
|
#if TOY_EDF == ENABLED
|
||||||
// Output the attitude
|
// Output the attitude
|
||||||
g.rc_1.servo_out = get_stabilize_roll(roll_rate);
|
g.rc_1.servo_out = get_stabilize_roll(roll_rate);
|
||||||
g.rc_2.servo_out = get_stabilize_pitch(0);
|
g.rc_2.servo_out = get_stabilize_pitch(g.rc_6.control_in); // use CH6 to trim pitch
|
||||||
|
|
||||||
#else
|
#else
|
||||||
// Output the attitude
|
// Output the attitude
|
||||||
|
Loading…
Reference in New Issue
Block a user