Skip to content

Commit 5d01491

Browse files
committed
ran formmater
1 parent e5a420d commit 5d01491

File tree

10 files changed

+123
-119
lines changed

10 files changed

+123
-119
lines changed

comms/mavlink/mavlink.cpp

Lines changed: 17 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@ Mavlink::Mavlink(Board & board)
4242

4343
void Mavlink::init(uint32_t baud_rate, uint32_t dev)
4444
{
45-
system_id_ = 1 ; //= static_cast<uint8_t>(RF_.params_.get_param_int(PARAM_SYSTEM_ID));
45+
system_id_ = 1; //= static_cast<uint8_t>(RF_.params_.get_param_int(PARAM_SYSTEM_ID));
4646
board_.serial_init(baud_rate, dev);
4747
initialized_ = true;
4848
}
@@ -218,7 +218,7 @@ void Mavlink::handle_msg_offboard_control(const mavlink_message_t * const msg,
218218
}
219219

220220
void Mavlink::handle_msg_offboard_control_full(const mavlink_message_t * const msg,
221-
CommMessage * message)
221+
CommMessage * message)
222222
{
223223
message->type = CommMessageType::MESSAGE_OFFBOARD_CONTROL;
224224
mavlink_offboard_control_full_t ctrl;
@@ -283,8 +283,8 @@ void Mavlink::send_baro(const PressureStruct & baro)
283283
send_message(msg);
284284
}
285285

286-
void Mavlink::send_command_ack(uint64_t timestamp_us,
287-
CommMessageCommand rosflight_cmd, RosflightCmdResponse success)
286+
void Mavlink::send_command_ack(uint64_t timestamp_us, CommMessageCommand rosflight_cmd,
287+
RosflightCmdResponse success)
288288
{
289289
(void) timestamp_us; // unused
290290
mavlink_message_t msg;
@@ -299,10 +299,9 @@ void Mavlink::send_command_ack(uint64_t timestamp_us,
299299
void Mavlink::send_diff_pressure(const PressureStruct & p)
300300
{
301301

302-
float ias = (p.pressure<0.0?-1.0:1.0)*sqrt(fabs(p.pressure) / (0.5 * 1.225));
302+
float ias = (p.pressure < 0.0 ? -1.0 : 1.0) * sqrt(fabs(p.pressure) / (0.5 * 1.225));
303303
mavlink_message_t msg;
304-
mavlink_msg_diff_pressure_pack(system_id_, compid_, &msg, ias,
305-
p.pressure, p.temperature);
304+
mavlink_msg_diff_pressure_pack(system_id_, compid_, &msg, ias, p.pressure, p.temperature);
306305
send_message(msg);
307306
}
308307

@@ -318,8 +317,9 @@ void Mavlink::send_heartbeat(uint64_t timestamp_us, bool fixed_wing)
318317
void Mavlink::send_imu(const ImuStruct & imu)
319318
{
320319
mavlink_message_t msg;
321-
mavlink_msg_small_imu_pack(system_id_, compid_, &msg, imu.header.timestamp, imu.accel[0], imu.accel[1],
322-
imu.accel[2], imu.gyro[0], imu.gyro[1], imu.gyro[2], imu.temperature);
320+
mavlink_msg_small_imu_pack(system_id_, compid_, &msg, imu.header.timestamp, imu.accel[0],
321+
imu.accel[1], imu.accel[2], imu.gyro[0], imu.gyro[1], imu.gyro[2],
322+
imu.temperature);
323323
send_message(msg, 0);
324324
}
325325

@@ -370,8 +370,7 @@ void Mavlink::send_gnss(const GnssStruct & gnss)
370370
}
371371
}
372372

373-
void Mavlink::send_log_message(uint64_t timestamp_us, LogSeverity severity,
374-
const char * text)
373+
void Mavlink::send_log_message(uint64_t timestamp_us, LogSeverity severity, const char * text)
375374
{
376375
(void) timestamp_us; // unused
377376
MAV_SEVERITY mavlink_severity = MAV_SEVERITY_ENUM_END;
@@ -412,8 +411,8 @@ void Mavlink::send_output_raw(const RcStruct & raw)
412411
send_message(msg);
413412
}
414413

415-
void Mavlink::send_param_value_int(uint64_t timestamp_us, uint16_t index,
416-
const char * const name, int32_t value, uint16_t param_count)
414+
void Mavlink::send_param_value_int(uint64_t timestamp_us, uint16_t index, const char * const name,
415+
int32_t value, uint16_t param_count)
417416
{
418417
(void) timestamp_us; // unused
419418
mavlink_param_union_t param;
@@ -425,8 +424,8 @@ void Mavlink::send_param_value_int(uint64_t timestamp_us, uint16_t index,
425424
send_message(msg);
426425
}
427426

428-
void Mavlink::send_param_value_float(uint64_t timestamp_us, uint16_t index,
429-
const char * const name, float value, uint16_t param_count)
427+
void Mavlink::send_param_value_float(uint64_t timestamp_us, uint16_t index, const char * const name,
428+
float value, uint16_t param_count)
430429
{
431430
(void) timestamp_us; // unused
432431
mavlink_message_t msg;
@@ -458,8 +457,8 @@ void Mavlink::send_sonar(const RangeStruct & range)
458457
send_message(msg);
459458
}
460459

461-
void Mavlink::send_status(uint64_t timestamp_us, bool armed, bool failsafe,
462-
bool rc_override, bool offboard, uint8_t error_code, uint8_t control_mode,
460+
void Mavlink::send_status(uint64_t timestamp_us, bool armed, bool failsafe, bool rc_override,
461+
bool offboard, uint8_t error_code, uint8_t control_mode,
463462
int16_t num_errors, int16_t loop_time_us)
464463
{
465464
(void) timestamp_us; // unused
@@ -485,8 +484,7 @@ void Mavlink::send_version(uint64_t timestamp_us, const char * const version)
485484
send_message(msg);
486485
}
487486

488-
void Mavlink::send_error_data(uint64_t timestamp_us,
489-
const StateManager::BackupData & error_data)
487+
void Mavlink::send_error_data(uint64_t timestamp_us, const StateManager::BackupData & error_data)
490488
{
491489
(void) timestamp_us; // unused
492490
mavlink_message_t msg;

comms/mavlink/mavlink.h

Lines changed: 14 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -71,41 +71,39 @@ class Mavlink : public CommLinkInterface
7171

7272
void send_imu(const ImuStruct & imu) override;
7373

74-
void send_log_message(uint64_t timestamp_us, LogSeverity severity,
75-
const char * text) override;
74+
void send_log_message(uint64_t timestamp_us, LogSeverity severity, const char * text) override;
7675

7776
void send_mag(const MagStruct & mag) override;
7877

79-
// void send_named_value_int(uint64_t timestamp_us, const char * const name,
80-
// int32_t value) override;
81-
//
82-
// void send_named_value_float(uint64_t imestamp_us, const char * const name,
83-
// float value) override;
78+
// void send_named_value_int(uint64_t timestamp_us, const char * const name,
79+
// int32_t value) override;
80+
//
81+
// void send_named_value_float(uint64_t imestamp_us, const char * const name,
82+
// float value) override;
8483

8584
void send_output_raw(const RcStruct & raw) override;
8685

87-
void send_param_value_int(uint64_t timestamp_us, uint16_t index,
88-
const char * const name, int32_t value, uint16_t param_count) override;
86+
void send_param_value_int(uint64_t timestamp_us, uint16_t index, const char * const name,
87+
int32_t value, uint16_t param_count) override;
8988

90-
void send_param_value_float(uint64_t timestamp_us, uint16_t index,
91-
const char * const name, float value, uint16_t param_count) override;
89+
void send_param_value_float(uint64_t timestamp_us, uint16_t index, const char * const name,
90+
float value, uint16_t param_count) override;
9291

9392
void send_rc_raw(const RcStruct & rc) override;
9493

9594
void send_sonar(const RangeStruct & sonar) override;
9695

97-
void send_status(uint64_t timestamp_us, bool armed, bool failsafe,
98-
bool rc_override, bool offboard, uint8_t error_code, uint8_t control_mode,
99-
int16_t num_errors, int16_t loop_time_us) override;
96+
void send_status(uint64_t timestamp_us, bool armed, bool failsafe, bool rc_override,
97+
bool offboard, uint8_t error_code, uint8_t control_mode, int16_t num_errors,
98+
int16_t loop_time_us) override;
10099

101100
void send_timesync(uint64_t timestamp_us, int64_t tc1, int64_t ts1) override;
102101

103102
void send_version(uint64_t timestamp_us, const char * const version) override;
104103

105104
void send_gnss(const GnssStruct & gnss) override;
106105

107-
void send_error_data(uint64_t timestamp_us,
108-
const StateManager::BackupData & error_data) override;
106+
void send_error_data(uint64_t timestamp_us, const StateManager::BackupData & error_data) override;
109107

110108
void send_battery_status(const BatteryStruct & batt) override;
111109

include/interface

include/mixer.h

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -35,8 +35,8 @@
3535
#include <cstdbool>
3636
#include <cstdint>
3737

38-
#include "sensors.h"
3938
#include "rc.h"
39+
#include "sensors.h"
4040

4141
namespace rosflight_firmware
4242
{
@@ -107,12 +107,11 @@ class Mixer
107107
MixerStruct output_raw_ = {};
108108

109109
//float raw_outputs_[NUM_TOTAL_OUTPUTS];
110-
float *raw_outputs_ = output_raw_.chan;
110+
float * raw_outputs_ = output_raw_.chan;
111111
float outputs_[NUM_TOTAL_OUTPUTS];
112112
aux_command_t aux_command_;
113113
output_type_t combined_output_type_[NUM_TOTAL_OUTPUTS];
114114

115-
116115
// clang-format off
117116

118117
const mixer_t esc_calibration_mixing = {

src/comm_manager.cpp

Lines changed: 2 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -190,10 +190,7 @@ void CommManager::send_diff_pressure(void)
190190
comm_link_.send_diff_pressure(*RF_.sensors_.get_diff_pressure());
191191
}
192192

193-
void CommManager::send_baro(void)
194-
{
195-
comm_link_.send_baro(*RF_.sensors_.get_baro());
196-
}
193+
void CommManager::send_baro(void) { comm_link_.send_baro(*RF_.sensors_.get_baro()); }
197194

198195
void CommManager::send_sonar(void) { comm_link_.send_sonar(*RF_.sensors_.get_sonar()); }
199196

@@ -407,8 +404,7 @@ void CommManager::receive_msg_rosflight_cmd(CommLinkInterface::CommMessage * mes
407404
CommLinkInterface::RosflightCmdResponse response =
408405
cast_in_range(result, CommLinkInterface::RosflightCmdResponse);
409406

410-
comm_link_.send_command_ack(RF_.board_.clock_micros(), message->rosflight_cmd_.command,
411-
response);
407+
comm_link_.send_command_ack(RF_.board_.clock_micros(), message->rosflight_cmd_.command, response);
412408

413409
if (reboot_flag || reboot_to_bootloader_flag) {
414410
RF_.board_.clock_delay(20);

src/rc.cpp

Lines changed: 6 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -57,10 +57,7 @@ void RC::init_rc()
5757
RcStruct * RC::get_rc(void) { return &rc_; }
5858
float RC::read_chan(uint8_t chan) { return rc_.chan[chan]; }
5959

60-
bool RC::receive(void)
61-
{
62-
return RF_.board_.rc_read(&rc_);
63-
}
60+
bool RC::receive(void) { return RF_.board_.rc_read(&rc_); }
6461

6562
void RC::param_change_callback(uint16_t param_id)
6663
{
@@ -175,7 +172,7 @@ bool RC::check_rc_lost()
175172
bool failsafe = false;
176173

177174
// If the board reports that we have lost RC, tell the state manager
178-
if(rc_.frameLost | rc_.failsafeActivated) {
175+
if (rc_.frameLost | rc_.failsafeActivated) {
179176
failsafe = true;
180177
} else {
181178
// go into failsafe if we get an invalid RC command for any channel
@@ -285,9 +282,10 @@ bool RC::new_command()
285282
}
286283
}
287284

288-
uint16_t RC::fake_rx(uint16_t *chan, uint16_t len, bool lost, bool failsafe) {
289-
len = (len<RC_STRUCT_CHANNELS)?len:RC_STRUCT_CHANNELS;
290-
for(int i=0;i<len;i++) rc_.chan[i] = (static_cast<float>(chan[i])-1000.)/1000.;
285+
uint16_t RC::fake_rx(uint16_t * chan, uint16_t len, bool lost, bool failsafe)
286+
{
287+
len = (len < RC_STRUCT_CHANNELS) ? len : RC_STRUCT_CHANNELS;
288+
for (int i = 0; i < len; i++) rc_.chan[i] = (static_cast<float>(chan[i]) - 1000.) / 1000.;
291289
rc_.failsafeActivated = failsafe;
292290
rc_.frameLost = lost;
293291
rc_.nChan = RC_STRUCT_CHANNELS;
@@ -297,5 +295,4 @@ uint16_t RC::fake_rx(uint16_t *chan, uint16_t len, bool lost, bool failsafe) {
297295
return len;
298296
};
299297

300-
301298
} // namespace rosflight_firmware

src/rosflight.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -44,8 +44,7 @@ ROSflight::ROSflight(Board & board, CommLinkInterface & comm_link)
4444
, rc_(*this)
4545
, sensors_(*this)
4646
, state_manager_(*this)
47-
{
48-
}
47+
{}
4948

5049
// Initialization Routine
5150
void ROSflight::init()

0 commit comments

Comments
 (0)