Skip to content

Commit

Permalink
Merge branch 'master' into master
Browse files Browse the repository at this point in the history
  • Loading branch information
setupfpv authored Sep 12, 2024
2 parents fcf3037 + f3b4f8f commit 2001063
Show file tree
Hide file tree
Showing 15 changed files with 497 additions and 107 deletions.
12 changes: 11 additions & 1 deletion ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -538,6 +538,15 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = {
// @User: Standard
AP_GROUPINFO("BCK_PIT_LIM", 38, QuadPlane, q_bck_pitch_lim, 10.0f),

// @Param: APPROACH_DIST
// @DisplayName: Q mode approach distance
// @Description: The minimum distance from the destination to use the fixed wing airbrake and approach code for landing approach. This is useful if you don't want the fixed wing approach logic to be used when you are close to the destination. Set to zero to always use fixed wing approach.
// @Units: m
// @Range: 0.0 1000
// @Increment: 1
// @User: Standard
AP_GROUPINFO("APPROACH_DIST", 39, QuadPlane, approach_distance, 0),

AP_GROUPEND
};

Expand Down Expand Up @@ -2160,7 +2169,8 @@ void QuadPlane::run_xy_controller(float accel_limit)
void QuadPlane::poscontrol_init_approach(void)
{
const float dist = plane.current_loc.get_distance(plane.next_WP_loc);
if (option_is_set(QuadPlane::OPTION::DISABLE_APPROACH)) {
if (option_is_set(QuadPlane::OPTION::DISABLE_APPROACH) ||
(is_positive(approach_distance) && dist < approach_distance)) {
// go straight to QPOS_POSITION1
poscontrol.set_state(QPOS_POSITION1);
gcs().send_text(MAV_SEVERITY_INFO,"VTOL Position1 d=%.1f", dist);
Expand Down
3 changes: 3 additions & 0 deletions ArduPlane/quadplane.h
Original file line number Diff line number Diff line change
Expand Up @@ -609,6 +609,9 @@ class QuadPlane
return (options.get() & int32_t(option)) != 0;
}

// minimum distance to be from destination to use approach logic
AP_Float approach_distance;

AP_Float takeoff_failure_scalar;
AP_Float maximum_takeoff_airspeed;
uint32_t takeoff_start_time_ms;
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/param_metadata/param_parse.py
Original file line number Diff line number Diff line change
Expand Up @@ -444,7 +444,7 @@ def clean_param(param):
for i in valueList:
(start, sep, end) = i.partition(":")
if sep != ":":
raise ValueError("Expected a colon seperator in (%s)" % (i,))
raise ValueError("Expected a colon separator in (%s)" % (i,))
if len(end) == 0:
raise ValueError("Expected a colon-separated string, got (%s)" % i)
end = end.strip()
Expand Down
64 changes: 0 additions & 64 deletions Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -2597,13 +2597,6 @@ def get_sim_parameter_documentation_get_whitelist(self):
"SIM_BARO_WCF_UP",
"SIM_FTOWESC_ENA",
"SIM_FTOWESC_POW",
"SIM_GND_BEHAV",
"SIM_GYR1_RND",
"SIM_GYR2_RND",
"SIM_GYR3_RND",
"SIM_GYR4_RND",
"SIM_GYR5_RND",
"SIM_GYR_FAIL_MSK",
"SIM_IE24_ENABLE",
"SIM_IE24_ERROR",
"SIM_IE24_STATE",
Expand Down Expand Up @@ -2712,15 +2705,6 @@ def get_sim_parameter_documentation_get_whitelist(self):
"SIM_IMUT5_GYR3_Z",
"SIM_IMUT5_TMAX",
"SIM_IMUT5_TMIN",
"SIM_IMUT_END",
"SIM_IMUT_FIXED",
"SIM_IMUT_START",
"SIM_IMUT_TCONST",
"SIM_INS_THR_MIN",
"SIM_LED_LAYOUT",
"SIM_LOOP_DELAY",
"SIM_MAG1_SCALING",
"SIM_MAG2_DEVID",
"SIM_MAG2_DIA_X",
"SIM_MAG2_DIA_Y",
"SIM_MAG2_DIA_Z",
Expand All @@ -2730,9 +2714,6 @@ def get_sim_parameter_documentation_get_whitelist(self):
"SIM_MAG2_OFS_X",
"SIM_MAG2_OFS_Y",
"SIM_MAG2_OFS_Z",
"SIM_MAG2_ORIENT",
"SIM_MAG2_SCALING",
"SIM_MAG3_DEVID",
"SIM_MAG3_DIA_X",
"SIM_MAG3_DIA_Y",
"SIM_MAG3_DIA_Z",
Expand All @@ -2742,18 +2723,9 @@ def get_sim_parameter_documentation_get_whitelist(self):
"SIM_MAG3_OFS_X",
"SIM_MAG3_OFS_Y",
"SIM_MAG3_OFS_Z",
"SIM_MAG3_ORIENT",
"SIM_MAG3_SCALING",
"SIM_MAG4_DEVID",
"SIM_MAG5_DEVID",
"SIM_MAG6_DEVID",
"SIM_MAG7_DEVID",
"SIM_MAG8_DEVID",
"SIM_MAG_ALY_HGT",
"SIM_MAG_ALY_X",
"SIM_MAG_ALY_Y",
"SIM_MAG_ALY_Z",
"SIM_MAG_DELAY",
"SIM_MAG1_DIA_X",
"SIM_MAG1_DIA_Y",
"SIM_MAG1_DIA_Z",
Expand All @@ -2766,16 +2738,10 @@ def get_sim_parameter_documentation_get_whitelist(self):
"SIM_MAG1_OFS_X",
"SIM_MAG1_OFS_Y",
"SIM_MAG1_OFS_Z",
"SIM_MAG1_ORIENT",
"SIM_MAG_RND",
"SIM_ODOM_ENABLE",
"SIM_PARA_ENABLE",
"SIM_PARA_PIN",
"SIM_PIN_MASK",
"SIM_PLD_ALT_LMT",
"SIM_PLD_DIST_LMT",
"SIM_RATE_HZ",
"SIM_RC_CHANCOUNT",
"SIM_RICH_CTRL",
"SIM_RICH_ENABLE",
"SIM_SHIP_DSIZE",
Expand All @@ -2786,43 +2752,13 @@ def get_sim_parameter_documentation_get_whitelist(self):
"SIM_SHIP_PSIZE",
"SIM_SHIP_SPEED",
"SIM_SHIP_SYSID",
"SIM_SHOVE_TIME",
"SIM_SHOVE_X",
"SIM_SHOVE_Y",
"SIM_SHOVE_Z",
"SIM_SONAR_GLITCH",
"SIM_SONAR_POS_X",
"SIM_SONAR_POS_Y",
"SIM_SONAR_POS_Z",
"SIM_SONAR_RND",
"SIM_SONAR_ROT",
"SIM_SONAR_SCALE",
"SIM_TA_ENABLE",
"SIM_TEMP_BFACTOR",
"SIM_TEMP_BRD_OFF",
"SIM_TEMP_START",
"SIM_TEMP_TCONST",
"SIM_TERRAIN",
"SIM_THML_SCENARI",
"SIM_TIDE_DIR",
"SIM_TIDE_SPEED",
"SIM_TIME_JITTER",
"SIM_TWIST_TIME",
"SIM_TWIST_X",
"SIM_TWIST_Y",
"SIM_TWIST_Z",
"SIM_VIB_FREQ_X",
"SIM_VIB_FREQ_Y",
"SIM_VIB_FREQ_Z",
"SIM_VIB_MOT_HMNC",
"SIM_VIB_MOT_MASK",
"SIM_VIB_MOT_MAX",
"SIM_VIB_MOT_MULT",
"SIM_WAVE_AMP",
"SIM_WAVE_DIR",
"SIM_WAVE_ENABLE",
"SIM_WAVE_LENGTH",
"SIM_WAVE_SPEED",
])

vinfo_key = self.vehicleinfo_key()
Expand Down
10 changes: 5 additions & 5 deletions libraries/AP_EFI/AP_EFI.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -252,16 +252,16 @@ void AP_EFI::log_status(void)
"TimeUS,Inst,IgnT,InjT,CHT,EGT,Lambda,CHT2,EGT2,IDX",
"s#dsOO-OO-",
"F-0C000000",
"QBfffffBff",
"QBffffffff",
AP_HAL::micros64(),
0,
state.cylinder_status.ignition_timing_deg,
state.cylinder_status.injection_time_ms,
state.cylinder_status.cylinder_head_temperature,
state.cylinder_status.exhaust_gas_temperature,
KELVIN_TO_C(state.cylinder_status.cylinder_head_temperature),
KELVIN_TO_C(state.cylinder_status.exhaust_gas_temperature),
state.cylinder_status.lambda_coefficient,
state.cylinder_status.cylinder_head_temperature2,
state.cylinder_status.exhaust_gas_temperature2,
KELVIN_TO_C(state.cylinder_status.cylinder_head_temperature2),
KELVIN_TO_C(state.cylinder_status.exhaust_gas_temperature2),
state.ecu_index);
}
#endif // LOGGING_ENABLED
Expand Down
30 changes: 15 additions & 15 deletions libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -484,19 +484,19 @@ const char* AP_ExternalAHRS_VectorNav::get_name() const
}

// Input data struct for EAHA logging message, used by both AHRS mode and INS mode
struct AP_ExternalAHRS_VectorNav::EAHA {
struct AP_ExternalAHRS_VectorNav::VNAT {
uint64_t timeUs;
float quat[4];
float ypr[3];
float yprU[3];
};


void AP_ExternalAHRS_VectorNav::write_eaha(const EAHA& data_to_log) const {
void AP_ExternalAHRS_VectorNav::write_vnat(const VNAT& data_to_log) const {

#if HAL_LOGGING_ENABLED
// @LoggerMessage: EAHA
// @Description: External AHRS Attitude data
// @LoggerMessage: VNAT
// @Description: VectorNav Attitude data
// @Field: TimeUS: Time since system startup
// @Field: Q1: Attitude quaternion 1
// @Field: Q2: Attitude quaternion 2
Expand All @@ -509,7 +509,7 @@ void AP_ExternalAHRS_VectorNav::write_eaha(const EAHA& data_to_log) const {
// @Field: PU: Pitch uncertainty
// @Field: RU: Roll uncertainty

AP::logger().WriteStreaming("EAHA", "TimeUS,Q1,Q2,Q3,Q4,Yaw,Pitch,Roll,YU,PU,RU",
AP::logger().WriteStreaming("VNAT", "TimeUS,Q1,Q2,Q3,Q4,Yaw,Pitch,Roll,YU,PU,RU",
"s----dddddd", "F0000000000",
"Qffffffffff",
data_to_log.timeUs,
Expand Down Expand Up @@ -573,8 +573,8 @@ void AP_ExternalAHRS_VectorNav::process_imu_packet(const uint8_t *b)
}

#if HAL_LOGGING_ENABLED
// @LoggerMessage: EAHI
// @Description: External AHRS IMU data
// @LoggerMessage: VNIM
// @Description: VectorNav IMU data
// @Field: TimeUS: Time since system startup
// @Field: Temp: Temprature
// @Field: Pres: Pressure
Expand All @@ -588,7 +588,7 @@ void AP_ExternalAHRS_VectorNav::process_imu_packet(const uint8_t *b)
// @Field: GY: Rotation rate Y-axis
// @Field: GZ: Rotation rate Z-axis

AP::logger().WriteStreaming("EAHI", "TimeUS,Temp,Pres,MX,MY,MZ,AX,AY,AZ,GX,GY,GZ",
AP::logger().WriteStreaming("VNIM", "TimeUS,Temp,Pres,MX,MY,MZ,AX,AY,AZ,GX,GY,GZ",
"sdPGGGoooEEE", "F00000000000",
"Qfffffffffff",
AP_HAL::micros64(),
Expand All @@ -610,13 +610,13 @@ void AP_ExternalAHRS_VectorNav::process_ahrs_ekf_packet(const uint8_t *b) {
state.have_quaternion = true;

#if HAL_LOGGING_ENABLED
EAHA data_to_log;
VNAT data_to_log;
data_to_log.timeUs = AP_HAL::micros64();
memcpy(data_to_log.quat, pkt.quaternion, sizeof(pkt.quaternion));
memcpy(data_to_log.ypr, pkt.ypr, sizeof(pkt.ypr));
memcpy(data_to_log.yprU, pkt.yprU, sizeof(pkt.yprU));

write_eaha(data_to_log);
write_vnat(data_to_log);
#endif // HAL_LOGGING_ENABLED
}

Expand All @@ -638,16 +638,16 @@ void AP_ExternalAHRS_VectorNav::process_ins_ekf_packet(const uint8_t *b) {
state.have_location = true;

#if HAL_LOGGING_ENABLED
EAHA data_to_log;
VNAT data_to_log;
auto now = AP_HAL::micros64();
data_to_log.timeUs = now;
memcpy(data_to_log.quat, pkt.quaternion, sizeof(pkt.quaternion));
memcpy(data_to_log.ypr, pkt.ypr, sizeof(pkt.ypr));
memcpy(data_to_log.yprU, pkt.yprU, sizeof(pkt.yprU));
write_eaha(data_to_log);
write_vnat(data_to_log);

// @LoggerMessage: EAHK
// @Description: External AHRS INS Kalman Filter data
// @LoggerMessage: VNKF
// @Description: VectorNav INS Kalman Filter data
// @Field: TimeUS: Time since system startup
// @Field: InsStatus: VectorNav INS health status
// @Field: Lat: Latitude
Expand All @@ -659,7 +659,7 @@ void AP_ExternalAHRS_VectorNav::process_ins_ekf_packet(const uint8_t *b) {
// @Field: PosU: Filter estimated position uncertainty
// @Field: VelU: Filter estimated Velocity uncertainty

AP::logger().WriteStreaming("EAHK", "TimeUS,InsStatus,Lat,Lon,Alt,VelN,VelE,VelD,PosU,VelU",
AP::logger().WriteStreaming("VNKF", "TimeUS,InsStatus,Lat,Lon,Alt,VelN,VelE,VelD,PosU,VelU",
"s-ddmnnndn", "F000000000",
"QHdddfffff",
now,
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h
Original file line number Diff line number Diff line change
Expand Up @@ -65,8 +65,8 @@ class AP_ExternalAHRS_VectorNav : public AP_ExternalAHRS_backend {

void run_command(const char *fmt, ...);

struct EAHA;
void write_eaha(const EAHA& data_to_log) const;
struct VNAT;
void write_vnat(const VNAT& data_to_log) const;
void process_imu_packet(const uint8_t *b);
void process_ahrs_ekf_packet(const uint8_t *b);
void process_ins_ekf_packet(const uint8_t *b);
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/RCOutput.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2300,7 +2300,7 @@ void RCOutput::safety_update(void)
bool safety_pressed = palReadLine(HAL_GPIO_PIN_SAFETY_IN);
if (safety_pressed) {
AP_BoardConfig *brdconfig = AP_BoardConfig::get_singleton();
if (safety_press_count < 255) {
if (safety_press_count < UINT8_MAX) {
safety_press_count++;
}
if (brdconfig && brdconfig->safety_button_handle_pressed(safety_press_count)) {
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ESP32/RCOutput.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -317,7 +317,7 @@ void RCOutput::safety_update(void)
bool safety_pressed = gpio_get_level((gpio_num_t)HAL_GPIO_PIN_SAFETY_IN);
if (safety_pressed) {
AP_BoardConfig *brdconfig = AP_BoardConfig::get_singleton();
if (safety_press_count < 255) {
if (safety_press_count < UINT8_MAX) {
safety_press_count++;
}
if (brdconfig && brdconfig->safety_button_handle_pressed(safety_press_count)) {
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Mission/AP_Mission.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2553,7 +2553,7 @@ bool AP_Mission::distance_to_landing(uint16_t index, float &tot_distance, Locati
}

// run through remainder of mission to approximate a distance to landing
for (uint8_t i=0; i<255; i++) {
for (uint8_t i=0; i<UINT8_MAX; i++) {
// search until the end of the mission command list
for (uint16_t cmd_index = index; cmd_index < (unsigned)_cmd_total; cmd_index++) {
// get next command
Expand Down Expand Up @@ -2612,7 +2612,7 @@ bool AP_Mission::distance_to_mission_leg(uint16_t start_index, float &rejoin_dis

// run through remainder of mission to approximate a distance to landing
uint16_t index = start_index;
for (uint8_t i=0; i<255; i++) {
for (uint8_t i=0; i<UINT8_MAX; i++) {
// search until the end of the mission command list
for (uint16_t cmd_index = index; cmd_index <= (unsigned)_cmd_total; cmd_index++) {
if (get_next_cmd(cmd_index, temp_cmd, true, false)) {
Expand Down
Loading

0 comments on commit 2001063

Please sign in to comment.