mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 23:43:58 -04:00
Plane: make throttle signed (pos and neg)
This commit is contained in:
parent
5338a76a58
commit
1cb094f12e
@ -1110,7 +1110,7 @@ void Plane::demo_servos(uint8_t i)
|
|||||||
*/
|
*/
|
||||||
void Plane::adjust_nav_pitch_throttle(void)
|
void Plane::adjust_nav_pitch_throttle(void)
|
||||||
{
|
{
|
||||||
uint8_t throttle = throttle_percentage();
|
int8_t throttle = throttle_percentage();
|
||||||
if (throttle < aparm.throttle_cruise && flight_stage != AP_SpdHgtControl::FLIGHT_VTOL) {
|
if (throttle < aparm.throttle_cruise && flight_stage != AP_SpdHgtControl::FLIGHT_VTOL) {
|
||||||
float p = (aparm.throttle_cruise - throttle) / (float)aparm.throttle_cruise;
|
float p = (aparm.throttle_cruise - throttle) / (float)aparm.throttle_cruise;
|
||||||
nav_pitch_cd -= g.stab_pitch_down * 100.0f * p;
|
nav_pitch_cd -= g.stab_pitch_down * 100.0f * p;
|
||||||
|
@ -242,13 +242,12 @@ struct PACKED log_Control_Tuning {
|
|||||||
int16_t pitch;
|
int16_t pitch;
|
||||||
int16_t throttle_out;
|
int16_t throttle_out;
|
||||||
int16_t rudder_out;
|
int16_t rudder_out;
|
||||||
float accel_y;
|
int16_t throttle_dem;
|
||||||
};
|
};
|
||||||
|
|
||||||
// Write a control tuning packet. Total length : 22 bytes
|
// Write a control tuning packet. Total length : 22 bytes
|
||||||
void Plane::Log_Write_Control_Tuning()
|
void Plane::Log_Write_Control_Tuning()
|
||||||
{
|
{
|
||||||
Vector3f accel = ins.get_accel();
|
|
||||||
struct log_Control_Tuning pkt = {
|
struct log_Control_Tuning pkt = {
|
||||||
LOG_PACKET_HEADER_INIT(LOG_CTUN_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_CTUN_MSG),
|
||||||
time_us : AP_HAL::micros64(),
|
time_us : AP_HAL::micros64(),
|
||||||
@ -258,7 +257,7 @@ void Plane::Log_Write_Control_Tuning()
|
|||||||
pitch : (int16_t)ahrs.pitch_sensor,
|
pitch : (int16_t)ahrs.pitch_sensor,
|
||||||
throttle_out : (int16_t)channel_throttle->servo_out,
|
throttle_out : (int16_t)channel_throttle->servo_out,
|
||||||
rudder_out : (int16_t)channel_rudder->servo_out,
|
rudder_out : (int16_t)channel_rudder->servo_out,
|
||||||
accel_y : accel.y
|
throttle_dem : (int16_t)SpdHgt_Controller->get_throttle_demand()
|
||||||
};
|
};
|
||||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
@ -340,7 +339,7 @@ struct PACKED log_Sonar {
|
|||||||
float voltage;
|
float voltage;
|
||||||
float baro_alt;
|
float baro_alt;
|
||||||
float groundspeed;
|
float groundspeed;
|
||||||
uint8_t throttle;
|
int8_t throttle;
|
||||||
uint8_t count;
|
uint8_t count;
|
||||||
float correction;
|
float correction;
|
||||||
};
|
};
|
||||||
@ -361,7 +360,7 @@ void Plane::Log_Write_Sonar()
|
|||||||
voltage : rangefinder.voltage_mv()*0.001f,
|
voltage : rangefinder.voltage_mv()*0.001f,
|
||||||
baro_alt : barometer.get_altitude(),
|
baro_alt : barometer.get_altitude(),
|
||||||
groundspeed : gps.ground_speed(),
|
groundspeed : gps.ground_speed(),
|
||||||
throttle : (uint8_t)(100 * channel_throttle->norm_output()),
|
throttle : (int8_t)(100 * channel_throttle->norm_output()),
|
||||||
count : rangefinder_state.in_range_count,
|
count : rangefinder_state.in_range_count,
|
||||||
correction : rangefinder_state.correction
|
correction : rangefinder_state.correction
|
||||||
};
|
};
|
||||||
@ -483,11 +482,11 @@ static const struct LogStructure log_structure[] = {
|
|||||||
{ LOG_STARTUP_MSG, sizeof(log_Startup),
|
{ LOG_STARTUP_MSG, sizeof(log_Startup),
|
||||||
"STRT", "QBH", "TimeUS,SType,CTot" },
|
"STRT", "QBH", "TimeUS,SType,CTot" },
|
||||||
{ LOG_CTUN_MSG, sizeof(log_Control_Tuning),
|
{ LOG_CTUN_MSG, sizeof(log_Control_Tuning),
|
||||||
"CTUN", "Qcccchhf", "TimeUS,NavRoll,Roll,NavPitch,Pitch,ThrOut,RdrOut,AccY" },
|
"CTUN", "Qcccchhh", "TimeUS,NavRoll,Roll,NavPitch,Pitch,ThrOut,RdrOut,ThrDem" },
|
||||||
{ LOG_NTUN_MSG, sizeof(log_Nav_Tuning),
|
{ LOG_NTUN_MSG, sizeof(log_Nav_Tuning),
|
||||||
"NTUN", "QCfccccfIf", "TimeUS,Yaw,WpDist,TargBrg,NavBrg,AltErr,Arspd,Alt,GSpdCM,XT" },
|
"NTUN", "QCfccccfIf", "TimeUS,Yaw,WpDist,TargBrg,NavBrg,AltErr,Arspd,Alt,GSpdCM,XT" },
|
||||||
{ LOG_SONAR_MSG, sizeof(log_Sonar),
|
{ LOG_SONAR_MSG, sizeof(log_Sonar),
|
||||||
"SONR", "QHfffBBf", "TimeUS,DistCM,Volt,BaroAlt,GSpd,Thr,Cnt,Corr" },
|
"SONR", "QHfffbBf", "TimeUS,DistCM,Volt,BaroAlt,GSpd,Thr,Cnt,Corr" },
|
||||||
{ LOG_ARM_DISARM_MSG, sizeof(log_Arm_Disarm),
|
{ LOG_ARM_DISARM_MSG, sizeof(log_Arm_Disarm),
|
||||||
"ARM", "QBH", "TimeUS,ArmState,ArmChecks" },
|
"ARM", "QBH", "TimeUS,ArmState,ArmChecks" },
|
||||||
{ LOG_ATRP_MSG, sizeof(AP_AutoTune::log_ATRP),
|
{ LOG_ATRP_MSG, sizeof(AP_AutoTune::log_ATRP),
|
||||||
|
@ -915,7 +915,7 @@ private:
|
|||||||
void servo_write(uint8_t ch, uint16_t pwm);
|
void servo_write(uint8_t ch, uint16_t pwm);
|
||||||
bool should_log(uint32_t mask);
|
bool should_log(uint32_t mask);
|
||||||
void frsky_telemetry_send(void);
|
void frsky_telemetry_send(void);
|
||||||
uint8_t throttle_percentage(void);
|
int8_t throttle_percentage(void);
|
||||||
void change_arm_state(void);
|
void change_arm_state(void);
|
||||||
bool disarm_motors(void);
|
bool disarm_motors(void);
|
||||||
bool arm_motors(AP_Arming::ArmingMethod method);
|
bool arm_motors(AP_Arming::ArmingMethod method);
|
||||||
|
@ -753,9 +753,9 @@ void Plane::frsky_telemetry_send(void)
|
|||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
return throttle percentage from 0 to 100
|
return throttle percentage from 0 to 100 for normal use and -100 to 100 when using reverse thrust
|
||||||
*/
|
*/
|
||||||
uint8_t Plane::throttle_percentage(void)
|
int8_t Plane::throttle_percentage(void)
|
||||||
{
|
{
|
||||||
if (auto_state.vtol_mode) {
|
if (auto_state.vtol_mode) {
|
||||||
return quadplane.throttle_percentage();
|
return quadplane.throttle_percentage();
|
||||||
|
Loading…
Reference in New Issue
Block a user