Copter: usage of rc_3.servo_out to use motors.get_throttle

servo_out is no longer a data holder for control functions
This commit is contained in:
Robert Lefebvre 2015-05-23 13:51:52 -04:00 committed by Randy Mackay
parent 316196b12f
commit 70a9a5699c
5 changed files with 9 additions and 9 deletions

View File

@ -955,7 +955,7 @@ static void update_batt_compass(void)
if(g.compass_enabled) {
// update compass with throttle value - used for compassmot
compass.set_throttle((float)channel_throttle->servo_out/1000.0f);
compass.set_throttle(motors.get_throttle()/1000.0f);
compass.read();
// log compass information
if (should_log(MASK_LOG_COMPASS)) {

View File

@ -94,11 +94,11 @@ static void update_thr_average()
}
// get throttle output
int16_t throttle = channel_throttle->servo_out;
float throttle = motors.get_throttle();
// calc average throttle if we are in a level hover
if (throttle > g.throttle_min && abs(climb_rate) < 60 && labs(ahrs.roll_sensor) < 500 && labs(ahrs.pitch_sensor) < 500) {
throttle_average = throttle_average * 0.99f + (float)throttle * 0.01f;
throttle_average = throttle_average * 0.99f + throttle * 0.01f;
// update position controller
pos_control.set_throttle_hover(throttle_average);
}

View File

@ -397,7 +397,7 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
gps.ground_speed(),
gps.ground_speed(),
(ahrs.yaw_sensor / 100) % 360,
channel_throttle->servo_out/10,
(int16_t)(motors.get_throttle())/10,
current_loc.alt / 100.0f,
climb_rate / 100.0f);
}

View File

@ -216,7 +216,7 @@ static void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds)
// Write a Current data packet
static void Log_Write_Current()
{
DataFlash.Log_Write_Current(battery, channel_throttle->servo_out);
DataFlash.Log_Write_Current(battery, (int16_t)(motors.get_throttle()));
// also write power status
DataFlash.Log_Write_Power();
@ -301,7 +301,7 @@ struct PACKED log_Control_Tuning {
uint32_t time_ms;
int16_t throttle_in;
int16_t angle_boost;
int16_t throttle_out;
float throttle_out;
float desired_alt;
float inav_alt;
int32_t baro_alt;
@ -319,7 +319,7 @@ static void Log_Write_Control_Tuning()
time_ms : hal.scheduler->millis(),
throttle_in : channel_throttle->control_in,
angle_boost : attitude_control.angle_boost(),
throttle_out : channel_throttle->servo_out,
throttle_out : motors.get_throttle(),
desired_alt : pos_control.get_alt_target() / 100.0f,
inav_alt : inertial_nav.get_altitude() / 100.0f,
baro_alt : baro_alt,
@ -652,7 +652,7 @@ static const struct LogStructure log_structure[] PROGMEM = {
{ LOG_NAV_TUNING_MSG, sizeof(log_Nav_Tuning),
"NTUN", "Iffffffffff", "TimeMS,DPosX,DPosY,PosX,PosY,DVelX,DVelY,VelX,VelY,DAccX,DAccY" },
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
"CTUN", "Ihhhffecchh", "TimeMS,ThrIn,AngBst,ThrOut,DAlt,Alt,BarAlt,DSAlt,SAlt,DCRt,CRt" },
"CTUN", "Ihhfffecchh", "TimeMS,ThrIn,AngBst,ThrOut,DAlt,Alt,BarAlt,DSAlt,SAlt,DCRt,CRt" },
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
"PM", "HHIhBH", "NLon,NLoop,MaxT,PMT,I2CErr,INSErr" },
{ LOG_RATE_MSG, sizeof(log_Rate),

View File

@ -56,7 +56,7 @@ static void check_dynamic_flight(void)
moving = (velocity >= HELI_DYNAMIC_FLIGHT_SPEED_MIN);
}else{
// with no GPS lock base it on throttle and forward lean angle
moving = (channel_throttle->servo_out > 800 || ahrs.pitch_sensor < -1500);
moving = (motors.get_throttle() > 800.0 || ahrs.pitch_sensor < -1500);
}
if (moving) {