Skip to content

Commit 4f87cb0

Browse files
acfloriaJaeyoung-Lim
authored andcommitted
Fix format
1 parent 042b48a commit 4f87cb0

File tree

4 files changed

+59
-49
lines changed

4 files changed

+59
-49
lines changed

src/drivers/si7210/si7210_main.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -85,7 +85,8 @@ si7210_main(int argc, char *argv[])
8585
cli.support_keep_running = true;
8686

8787
int ch;
88-
while ((ch = cli.getopt(argc, argv, "")) != EOF) {}
88+
89+
while ((ch = cli.getopt(argc, argv, "")) != EOF) {}
8990

9091
const char *verb = cli.parseDefaultArguments(argc, argv);
9192

src/modules/mavlink/mavlink_messages.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -348,7 +348,7 @@ static const StreamListItem streams_list[] = {
348348
create_stream_list_item<MavlinkStreamScaledPressure3>(),
349349
#endif // SCALED_PRESSURE3
350350
#if defined(SENSOR_AIRFLOW_ANGLES_HPP)
351-
create_stream_list_item<MavlinkStreamSensorAirflowAngles>(),
351+
create_stream_list_item<MavlinkStreamSensorAirflowAngles>(),
352352
#endif // SENSOR_AIRFLOW_ANGLES
353353
#if defined(ACTUATOR_OUTPUT_STATUS_HPP)
354354
create_stream_list_item<MavlinkStreamActuatorOutputStatus>(),

src/modules/mavlink/streams/SENSOR_AIRFLOW_ANGLES.hpp

Lines changed: 38 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -50,11 +50,11 @@ class MavlinkStreamSensorAirflowAngles : public MavlinkStream
5050

5151
unsigned get_size() override
5252
{
53-
if (_airflow_aoa_sub.advertised() || _airflow_slip_sub.advertised()) {
54-
return MAVLINK_MSG_ID_SENSOR_AIRFLOW_ANGLES_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
55-
}
53+
if (_airflow_aoa_sub.advertised() || _airflow_slip_sub.advertised()) {
54+
return MAVLINK_MSG_ID_SENSOR_AIRFLOW_ANGLES_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
55+
}
5656

57-
return 0;
57+
return 0;
5858
}
5959

6060
private:
@@ -66,34 +66,40 @@ class MavlinkStreamSensorAirflowAngles : public MavlinkStream
6666
bool send() override
6767
{
6868
if (_airflow_aoa_sub.updated() || _airflow_slip_sub.updated()) {
69-
mavlink_sensor_airflow_angles_t msg{};
70-
71-
struct airflow_aoa_s airflow_aoa;
72-
if (_airflow_aoa_sub.copy(&airflow_aoa)) {
73-
msg.timestamp = airflow_aoa.timestamp / 1000;
74-
msg.angleofattack = math::degrees(airflow_aoa.aoa_rad);
75-
msg.angleofattack_valid = airflow_aoa.valid;
76-
} else {
77-
msg.timestamp = 0;
78-
msg.angleofattack = 0.0;
79-
msg.angleofattack_valid = false;
80-
}
81-
82-
struct airflow_slip_s airflow_slip;
83-
if (_airflow_slip_sub.copy(&airflow_slip)) {
84-
const uint64_t timestamp = airflow_slip.timestamp / 1000;
85-
if (timestamp > msg.timestamp) {
86-
msg.timestamp = timestamp;
87-
}
88-
msg.sideslip = math::degrees(airflow_slip.slip_rad);
89-
msg.sideslip_valid = airflow_slip.valid;
90-
} else {
91-
msg.timestamp = 0;
92-
msg.sideslip = 0.0;
93-
msg.sideslip_valid = false;
94-
}
95-
96-
mavlink_msg_sensor_airflow_angles_send_struct(_mavlink->get_channel(), &msg);
69+
mavlink_sensor_airflow_angles_t msg{};
70+
71+
struct airflow_aoa_s airflow_aoa;
72+
73+
if (_airflow_aoa_sub.copy(&airflow_aoa)) {
74+
msg.timestamp = airflow_aoa.timestamp / 1000;
75+
msg.angleofattack = math::degrees(airflow_aoa.aoa_rad);
76+
msg.angleofattack_valid = airflow_aoa.valid;
77+
78+
} else {
79+
msg.timestamp = 0;
80+
msg.angleofattack = 0.0;
81+
msg.angleofattack_valid = false;
82+
}
83+
84+
struct airflow_slip_s airflow_slip;
85+
86+
if (_airflow_slip_sub.copy(&airflow_slip)) {
87+
const uint64_t timestamp = airflow_slip.timestamp / 1000;
88+
89+
if (timestamp > msg.timestamp) {
90+
msg.timestamp = timestamp;
91+
}
92+
93+
msg.sideslip = math::degrees(airflow_slip.slip_rad);
94+
msg.sideslip_valid = airflow_slip.valid;
95+
96+
} else {
97+
msg.timestamp = 0;
98+
msg.sideslip = 0.0;
99+
msg.sideslip_valid = false;
100+
}
101+
102+
mavlink_msg_sensor_airflow_angles_send_struct(_mavlink->get_channel(), &msg);
97103

98104
return true;
99105
}

src/modules/sensors/sensors.cpp

Lines changed: 18 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -132,15 +132,15 @@ class Sensors : public ModuleBase<Sensors>, public ModuleParams, public px4::Sch
132132
uORB::Subscription _diff_pres_sub{ORB_ID(differential_pressure)};
133133
uORB::Subscription _vcontrol_mode_sub{ORB_ID(vehicle_control_mode)};
134134
uORB::Subscription _vehicle_air_data_sub{ORB_ID(vehicle_air_data)};
135-
uORB::Subscription _sensor_hall_subs[MAX_SENSOR_COUNT] { // could be set to ORB_MULTI_MAX_INSTANCES if needed
136-
{ORB_ID(sensor_hall), 0},
137-
{ORB_ID(sensor_hall), 1},
138-
{ORB_ID(sensor_hall), 2},
139-
{ORB_ID(sensor_hall), 3},
140-
};
135+
uORB::Subscription _sensor_hall_subs[MAX_SENSOR_COUNT] { // could be set to ORB_MULTI_MAX_INSTANCES if needed
136+
{ORB_ID(sensor_hall), 0},
137+
{ORB_ID(sensor_hall), 1},
138+
{ORB_ID(sensor_hall), 2},
139+
{ORB_ID(sensor_hall), 3},
140+
};
141141

142-
int _av_aoa_hall_sub_index = -1; // AoA vane index for hall effect subscription
143-
int _av_slip_hall_sub_index = -1; // Slip vane index for hall effect subscription
142+
int _av_aoa_hall_sub_index = -1; // AoA vane index for hall effect subscription
143+
int _av_slip_hall_sub_index = -1; // Slip vane index for hall effect subscription
144144

145145
uORB::Publication<airspeed_s> _airspeed_pub{ORB_ID(airspeed)};
146146
uORB::Publication<sensor_combined_s> _sensor_pub{ORB_ID(sensor_combined)};
@@ -442,7 +442,7 @@ void Sensors::diff_pres_poll()
442442
} else {
443443
// differential pressure temperature invalid, check barometer
444444
if ((air_data.timestamp != 0) && PX4_ISFINITE(air_data.baro_temp_celcius)
445-
&& (air_data.baro_temp_celcius >= -40.f) && (air_data.baro_temp_celcius <= 125.f)) {
445+
&& (air_data.baro_temp_celcius >= -40.f) && (air_data.baro_temp_celcius <= 125.f)) {
446446

447447
// TODO: review PCB_TEMP_ESTIMATE_DEG, ignore for external baro
448448
air_temperature_celsius = air_data.baro_temp_celcius - PCB_TEMP_ESTIMATE_DEG;
@@ -480,13 +480,13 @@ void Sensors::diff_pres_poll()
480480

481481
/* don't risk to feed negative airspeed into the system */
482482
airspeed.indicated_airspeed_m_s = calc_IAS_corrected((enum AIRSPEED_COMPENSATION_MODEL)
483-
_parameters.air_cmodel,
484-
smodel, _parameters.air_tube_length, _parameters.air_tube_diameter_mm,
485-
diff_pres.differential_pressure_filtered_pa, air_data.baro_pressure_pa,
486-
air_temperature_celsius);
483+
_parameters.air_cmodel,
484+
smodel, _parameters.air_tube_length, _parameters.air_tube_diameter_mm,
485+
diff_pres.differential_pressure_filtered_pa, air_data.baro_pressure_pa,
486+
air_temperature_celsius);
487487

488488
airspeed.true_airspeed_m_s = calc_TAS_from_CAS(airspeed.indicated_airspeed_m_s, air_data.baro_pressure_pa,
489-
air_temperature_celsius); // assume that CAS = IAS as we don't have an CAS-scale here
489+
air_temperature_celsius); // assume that CAS = IAS as we don't have an CAS-scale here
490490

491491
airspeed.air_temperature_celsius = air_temperature_celsius;
492492

@@ -593,6 +593,7 @@ void Sensors::hall_poll()
593593
if ((_av_aoa_hall_sub_index >= 0) && (_av_aoa_hall_sub_index < MAX_SENSOR_COUNT)) {
594594
// A hall sensor with selected driver ID for the AoA vane has been found/set
595595
struct sensor_hall_s sensor_hall;
596+
596597
if (_sensor_hall_subs[_av_aoa_hall_sub_index].update(&sensor_hall)) {
597598
airflow_aoa_s airflow_aoa;
598599
airflow_aoa.timestamp = hrt_absolute_time();
@@ -624,6 +625,7 @@ void Sensors::hall_poll()
624625
if ((_av_slip_hall_sub_index >= 0) && (_av_slip_hall_sub_index < MAX_SENSOR_COUNT)) {
625626
// A hall sensor with selected driver ID for the slip vane has been found/set
626627
struct sensor_hall_s sensor_hall;
628+
627629
if (_sensor_hall_subs[_av_slip_hall_sub_index].update(&sensor_hall)) {
628630
airflow_slip_s airflow_slip;
629631
airflow_slip.timestamp = hrt_absolute_time();
@@ -663,7 +665,7 @@ void Sensors::hall_poll()
663665
}
664666

665667
// find the Slip hall sensor index if not set yet
666-
if (_parameters.CAL_AV_SLIP_ID >= 0&& _av_slip_hall_sub_index < 0) {
668+
if (_parameters.CAL_AV_SLIP_ID >= 0 && _av_slip_hall_sub_index < 0) {
667669
_av_slip_hall_sub_index = getHallSubIndex(_parameters.CAL_AV_SLIP_ID);
668670

669671
if (_av_slip_hall_sub_index >= 0) {
@@ -676,6 +678,7 @@ int Sensors::getHallSubIndex(const int av_driver_id)
676678
{
677679
for (unsigned i = 0; i < MAX_SENSOR_COUNT; i++) {
678680
sensor_hall_s sensor_hall;
681+
679682
if (_sensor_hall_subs[i].copy(&sensor_hall)) {
680683
if (sensor_hall.instance == av_driver_id) {
681684
return i;

0 commit comments

Comments
 (0)