add space after function name and if statement (#21225)

pull/21227/head
Dean Lee 2021-06-11 16:17:52 +08:00 committed by GitHub
parent e7df9adfe3
commit e4e669bb0f
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
56 changed files with 294 additions and 294 deletions

View File

@ -51,7 +51,7 @@ void safety_setter_thread() {
// switch to SILENT when CarVin param is read
while (true) {
if (do_exit || !panda->connected){
if (do_exit || !panda->connected) {
safety_setter_thread_running = false;
return;
};
@ -72,7 +72,7 @@ void safety_setter_thread() {
std::string params;
LOGW("waiting for params to set safety model");
while (true) {
if (do_exit || !panda->connected){
if (do_exit || !panda->connected) {
safety_setter_thread_running = false;
return;
};
@ -124,7 +124,7 @@ bool usb_connect() {
// Convert to hex for offroad
char fw_sig_hex_buf[16] = {0};
const uint8_t *fw_sig_buf = fw_sig->data();
for (size_t i = 0; i < 8; i++){
for (size_t i = 0; i < 8; i++) {
fw_sig_hex_buf[2*i] = NIBBLE_TO_HEX((uint8_t)fw_sig_buf[i] >> 4);
fw_sig_hex_buf[2*i+1] = NIBBLE_TO_HEX((uint8_t)fw_sig_buf[i] & 0xF);
}
@ -146,7 +146,7 @@ bool usb_connect() {
}
#endif
if (tmp_panda->has_rtc){
if (tmp_panda->has_rtc) {
setenv("TZ","UTC",1);
struct tm sys_time = util::get_time();
struct tm rtc_time = tmp_panda->get_rtc();
@ -199,7 +199,7 @@ void can_send_thread(bool fake_send) {
while (!do_exit && panda->connected) {
Message * msg = subscriber->receive();
if (!msg){
if (!msg) {
if (errno == EINTR) {
do_exit = true;
}
@ -211,7 +211,7 @@ void can_send_thread(bool fake_send) {
//Dont send if older than 1 second
if (nanos_since_boot() - event.getLogMonoTime() < 1e9) {
if (!fake_send){
if (!fake_send) {
panda->can_send(event.getSendcan());
}
}
@ -241,7 +241,7 @@ void can_recv_thread() {
if (remaining > 0) {
std::this_thread::sleep_for(std::chrono::nanoseconds(remaining));
} else {
if (ignition){
if (ignition) {
LOGW("missed cycles (%d) %lld", (int)-1*remaining/dt, remaining);
}
next_frame_time = cur_time;
@ -292,7 +292,7 @@ void panda_state_thread(bool spoofing_started) {
#ifndef __x86_64__
bool power_save_desired = !ignition;
if (pandaState.power_save_enabled != power_save_desired){
if (pandaState.power_save_enabled != power_save_desired) {
panda->set_power_saving(power_save_desired);
}
@ -317,12 +317,12 @@ void panda_state_thread(bool spoofing_started) {
}
// Write to rtc once per minute when no ignition present
if ((panda->has_rtc) && !ignition && (no_ignition_cnt % 120 == 1)){
if ((panda->has_rtc) && !ignition && (no_ignition_cnt % 120 == 1)) {
// Write time to RTC if it looks reasonable
setenv("TZ","UTC",1);
struct tm sys_time = util::get_time();
if (util::time_valid(sys_time)){
if (util::time_valid(sys_time)) {
struct tm rtc_time = panda->get_rtc();
double seconds = difftime(mktime(&rtc_time), mktime(&sys_time));
@ -388,7 +388,7 @@ void panda_state_thread(bool spoofing_started) {
size_t i = 0;
for (size_t f = size_t(cereal::PandaState::FaultType::RELAY_MALFUNCTION);
f <= size_t(cereal::PandaState::FaultType::INTERRUPT_RATE_TIM9); f++){
f <= size_t(cereal::PandaState::FaultType::INTERRUPT_RATE_TIM9); f++) {
if (fault_bits.test(f)) {
faults.set(i, cereal::PandaState::FaultType(f));
i++;
@ -415,11 +415,11 @@ void hardware_control_thread() {
cnt++;
sm.update(1000); // TODO: what happens if EINTR is sent while in sm.update?
if (!Hardware::PC() && sm.updated("deviceState")){
if (!Hardware::PC() && sm.updated("deviceState")) {
// Charging mode
bool charging_disabled = sm["deviceState"].getDeviceState().getChargingDisabled();
if (charging_disabled != prev_charging_disabled){
if (charging_disabled){
if (charging_disabled != prev_charging_disabled) {
if (charging_disabled) {
panda->set_usb_power_mode(cereal::PandaState::UsbPowerMode::CLIENT);
LOGW("TURN OFF CHARGING!\n");
} else {
@ -432,15 +432,15 @@ void hardware_control_thread() {
// Other pandas don't have fan/IR to control
if (panda->hw_type != cereal::PandaState::PandaType::UNO && panda->hw_type != cereal::PandaState::PandaType::DOS) continue;
if (sm.updated("deviceState")){
if (sm.updated("deviceState")) {
// Fan speed
uint16_t fan_speed = sm["deviceState"].getDeviceState().getFanSpeedPercentDesired();
if (fan_speed != prev_fan_speed || cnt % 100 == 0){
if (fan_speed != prev_fan_speed || cnt % 100 == 0) {
panda->set_fan_speed(fan_speed);
prev_fan_speed = fan_speed;
}
}
if (sm.updated("driverCameraState")){
if (sm.updated("driverCameraState")) {
auto event = sm["driverCameraState"];
int cur_integ_lines = event.getDriverCameraState().getIntegLines();
last_front_frame_t = event.getLogMonoTime();
@ -455,11 +455,11 @@ void hardware_control_thread() {
}
// Disable ir_pwr on front frame timeout
uint64_t cur_t = nanos_since_boot();
if (cur_t - last_front_frame_t > 1e9){
if (cur_t - last_front_frame_t > 1e9) {
ir_pwr = 0;
}
if (ir_pwr != prev_ir_pwr || cnt % 100 == 0 || ir_pwr >= 50.0){
if (ir_pwr != prev_ir_pwr || cnt % 100 == 0 || ir_pwr >= 50.0) {
panda->set_ir_pwr(ir_pwr);
prev_ir_pwr = ir_pwr;
}
@ -492,10 +492,10 @@ void pigeon_thread() {
// Parse message header
if (ignition && recv.length() >= 3) {
if (recv[0] == (char)ublox::PREAMBLE1 && recv[1] == (char)ublox::PREAMBLE2){
if (recv[0] == (char)ublox::PREAMBLE1 && recv[1] == (char)ublox::PREAMBLE2) {
const char msg_cls = recv[2];
uint64_t t = nanos_since_boot();
if (t > last_recv_time[msg_cls]){
if (t > last_recv_time[msg_cls]) {
last_recv_time[msg_cls] = t;
}
}
@ -512,12 +512,12 @@ void pigeon_thread() {
}
// Check based on null bytes
if (ignition && recv.length() > 0 && recv[0] == (char)0x00){
if (ignition && recv.length() > 0 && recv[0] == (char)0x00) {
need_reset = true;
LOGW("received invalid ublox message while onroad, resetting panda GPS");
}
if (recv.length() > 0){
if (recv.length() > 0) {
pigeon_publish_raw(pm, recv);
}
@ -559,7 +559,7 @@ int main() {
err = set_core_affinity(Hardware::TICI() ? 4 : 3);
LOG("set affinity returns %d", err);
while (!do_exit){
while (!do_exit) {
std::vector<std::thread> threads;
threads.push_back(std::thread(panda_state_thread, getenv("STARTED") != nullptr));

View File

@ -11,7 +11,7 @@
#include "selfdrive/common/swaglog.h"
#include "selfdrive/common/util.h"
Panda::Panda(){
Panda::Panda() {
// init libusb
int err = libusb_init(&ctx);
if (err != 0) { goto fail; }
@ -50,14 +50,14 @@ fail:
throw std::runtime_error("Error connecting to panda");
}
Panda::~Panda(){
Panda::~Panda() {
std::lock_guard lk(usb_lock);
cleanup();
connected = false;
}
void Panda::cleanup(){
if (dev_handle){
void Panda::cleanup() {
if (dev_handle) {
libusb_release_interface(dev_handle, 0);
libusb_close(dev_handle);
}
@ -80,7 +80,7 @@ int Panda::usb_write(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigne
int err;
const uint8_t bmRequestType = LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE;
if (!connected){
if (!connected) {
return LIBUSB_ERROR_NO_DEVICE;
}
@ -97,7 +97,7 @@ int Panda::usb_read(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigned
int err;
const uint8_t bmRequestType = LIBUSB_ENDPOINT_IN | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE;
if (!connected){
if (!connected) {
return LIBUSB_ERROR_NO_DEVICE;
}
@ -114,7 +114,7 @@ int Panda::usb_bulk_write(unsigned char endpoint, unsigned char* data, int lengt
int err;
int transferred = 0;
if (!connected){
if (!connected) {
return 0;
}
@ -139,7 +139,7 @@ int Panda::usb_bulk_read(unsigned char endpoint, unsigned char* data, int length
int err;
int transferred = 0;
if (!connected){
if (!connected) {
return 0;
}
@ -162,7 +162,7 @@ int Panda::usb_bulk_read(unsigned char endpoint, unsigned char* data, int length
return transferred;
}
void Panda::set_safety_model(cereal::CarParams::SafetyModel safety_model, int safety_param){
void Panda::set_safety_model(cereal::CarParams::SafetyModel safety_model, int safety_param) {
usb_write(0xdc, (uint16_t)safety_model, safety_param);
}
@ -177,7 +177,7 @@ cereal::PandaState::PandaType Panda::get_hw_type() {
return (cereal::PandaState::PandaType)(hw_query[0]);
}
void Panda::set_rtc(struct tm sys_time){
void Panda::set_rtc(struct tm sys_time) {
// tm struct has year defined as years since 1900
usb_write(0xa1, (uint16_t)(1900 + sys_time.tm_year), 0);
usb_write(0xa2, (uint16_t)(1 + sys_time.tm_mon), 0);
@ -188,7 +188,7 @@ void Panda::set_rtc(struct tm sys_time){
usb_write(0xa7, (uint16_t)sys_time.tm_sec, 0);
}
struct tm Panda::get_rtc(){
struct tm Panda::get_rtc() {
struct __attribute__((packed)) timestamp_t {
uint16_t year; // Starts at 0
uint8_t month;
@ -212,11 +212,11 @@ struct tm Panda::get_rtc(){
return new_time;
}
void Panda::set_fan_speed(uint16_t fan_speed){
void Panda::set_fan_speed(uint16_t fan_speed) {
usb_write(0xb1, fan_speed, 0);
}
uint16_t Panda::get_fan_speed(){
uint16_t Panda::get_fan_speed() {
uint16_t fan_speed_rpm = 0;
usb_read(0xb2, 0, 0, (unsigned char*)&fan_speed_rpm, sizeof(fan_speed_rpm));
return fan_speed_rpm;
@ -226,17 +226,17 @@ void Panda::set_ir_pwr(uint16_t ir_pwr) {
usb_write(0xb0, ir_pwr, 0);
}
health_t Panda::get_state(){
health_t Panda::get_state() {
health_t health {0};
usb_read(0xd2, 0, 0, (unsigned char*)&health, sizeof(health));
return health;
}
void Panda::set_loopback(bool loopback){
void Panda::set_loopback(bool loopback) {
usb_write(0xe5, loopback, 0);
}
std::optional<std::vector<uint8_t>> Panda::get_firmware_version(){
std::optional<std::vector<uint8_t>> Panda::get_firmware_version() {
std::vector<uint8_t> fw_sig_buf(128);
int read_1 = usb_read(0xd3, 0, 0, &fw_sig_buf[0], 64);
int read_2 = usb_read(0xd4, 0, 0, &fw_sig_buf[64], 64);
@ -249,19 +249,19 @@ std::optional<std::string> Panda::get_serial() {
return err >= 0 ? std::make_optional(serial_buf) : std::nullopt;
}
void Panda::set_power_saving(bool power_saving){
void Panda::set_power_saving(bool power_saving) {
usb_write(0xe7, power_saving, 0);
}
void Panda::set_usb_power_mode(cereal::PandaState::UsbPowerMode power_mode){
void Panda::set_usb_power_mode(cereal::PandaState::UsbPowerMode power_mode) {
usb_write(0xe6, (uint16_t)power_mode, 0);
}
void Panda::send_heartbeat(){
void Panda::send_heartbeat() {
usb_write(0xf3, 1, 0);
}
void Panda::can_send(capnp::List<cereal::CanData>::Reader can_data_list){
void Panda::can_send(capnp::List<cereal::CanData>::Reader can_data_list) {
static std::vector<uint32_t> send;
const int msg_count = can_data_list.size();

View File

@ -27,26 +27,26 @@ const std::string nack = "\xb5\x62\x05\x00\x02\x00";
const std::string sos_ack = "\xb5\x62\x09\x14\x08\x00\x02\x00\x00\x00\x01\x00\x00\x00";
const std::string sos_nack = "\xb5\x62\x09\x14\x08\x00\x02\x00\x00\x00\x00\x00\x00\x00";
Pigeon * Pigeon::connect(Panda * p){
Pigeon * Pigeon::connect(Panda * p) {
PandaPigeon * pigeon = new PandaPigeon();
pigeon->connect(p);
return pigeon;
}
Pigeon * Pigeon::connect(const char * tty){
Pigeon * Pigeon::connect(const char * tty) {
TTYPigeon * pigeon = new TTYPigeon();
pigeon->connect(tty);
return pigeon;
}
bool Pigeon::wait_for_ack(const std::string &ack, const std::string &nack){
bool Pigeon::wait_for_ack(const std::string &ack, const std::string &nack) {
std::string s;
while (!do_exit){
while (!do_exit) {
s += receive();
if (s.find(ack) != std::string::npos){
if (s.find(ack) != std::string::npos) {
LOGD("Received ACK from ublox");
return true;
} else if (s.find(nack) != std::string::npos) {
@ -62,17 +62,17 @@ bool Pigeon::wait_for_ack(const std::string &ack, const std::string &nack){
return false;
}
bool Pigeon::wait_for_ack(){
bool Pigeon::wait_for_ack() {
return wait_for_ack(ack, nack);
}
bool Pigeon::send_with_ack(const std::string &cmd){
bool Pigeon::send_with_ack(const std::string &cmd) {
send(cmd);
return wait_for_ack();
}
void Pigeon::init() {
for (int i = 0; i < 10; i++){
for (int i = 0; i < 10; i++) {
if (do_exit) return;
LOGW("panda GPS start");
@ -118,7 +118,7 @@ void Pigeon::init() {
if (!send_with_ack("\xB5\x62\x06\x01\x03\x00\x0A\x0B\x01\x20\x74"s)) continue;
auto time = util::get_time();
if (util::time_valid(time)){
if (util::time_valid(time)) {
LOGW("Sending current time to ublox");
send(ublox::build_ubx_mga_ini_time_utc(time));
}
@ -129,7 +129,7 @@ void Pigeon::init() {
LOGE("failed to initialize panda GPS");
}
void Pigeon::stop(){
void Pigeon::stop() {
LOGW("Storing almanac in ublox flash");
// Controlled GNSS stop
@ -172,7 +172,7 @@ std::string PandaPigeon::receive() {
std::string r;
r.reserve(0x1000 + 0x40);
unsigned char dat[0x40];
while (r.length() < 0x1000){
while (r.length() < 0x1000) {
int len = panda->usb_read(0xe0, 1, 0, dat, sizeof(dat));
if (len <= 0) break;
r.append((char*)dat, len);
@ -185,7 +185,7 @@ void PandaPigeon::set_power(bool power) {
panda->usb_write(0xd9, power, 0);
}
PandaPigeon::~PandaPigeon(){
PandaPigeon::~PandaPigeon() {
}
void handle_tty_issue(int err, const char func[]) {
@ -194,7 +194,7 @@ void handle_tty_issue(int err, const char func[]) {
void TTYPigeon::connect(const char * tty) {
pigeon_tty_fd = open(tty, O_RDWR);
if (pigeon_tty_fd < 0){
if (pigeon_tty_fd < 0) {
handle_tty_issue(errno, __func__);
assert(pigeon_tty_fd >= 0);
}
@ -222,9 +222,9 @@ void TTYPigeon::connect(const char * tty) {
assert(err == 0);
}
void TTYPigeon::set_baud(int baud){
void TTYPigeon::set_baud(int baud) {
speed_t baud_const = 0;
switch(baud){
switch(baud) {
case 9600:
baud_const = B9600;
break;
@ -264,11 +264,11 @@ std::string TTYPigeon::receive() {
std::string r;
r.reserve(0x1000 + 0x40);
char dat[0x40];
while (r.length() < 0x1000){
while (r.length() < 0x1000) {
int len = read(pigeon_tty_fd, dat, sizeof(dat));
if(len < 0) {
handle_tty_issue(len, __func__);
} else if (len == 0){
} else if (len == 0) {
break;
} else {
r.append(dat, len);
@ -278,7 +278,7 @@ std::string TTYPigeon::receive() {
return r;
}
void TTYPigeon::set_power(bool power){
void TTYPigeon::set_power(bool power) {
#ifdef QCOM2
int err = 0;
err += gpio_init(GPIO_UBLOX_RST_N, true);
@ -292,6 +292,6 @@ void TTYPigeon::set_power(bool power){
#endif
}
TTYPigeon::~TTYPigeon(){
TTYPigeon::~TTYPigeon() {
close(pigeon_tty_fd);
}

View File

@ -163,7 +163,7 @@ bool CameraBuf::acquire() {
}
void CameraBuf::release() {
if (release_callback){
if (release_callback) {
release_callback((void*)camera_state, cur_buf_idx);
}
}

View File

@ -50,7 +50,7 @@ void run_frame_stream(CameraState &camera, const char* frame_pkt) {
size_t buf_idx = 0;
while (!do_exit) {
sm.update(1000);
if(sm.updated(frame_pkt)){
if(sm.updated(frame_pkt)) {
auto msg = static_cast<capnp::DynamicStruct::Reader>(sm[frame_pkt]);
auto frame = msg.get(frame_pkt).as<capnp::DynamicStruct>();
camera.buf.camera_bufs_metadata[buf_idx] = {

View File

@ -848,7 +848,7 @@ static void parse_autofocus(CameraState *s, uint8_t *d) {
static std::optional<float> get_accel_z(SubMaster *sm) {
sm->update(0);
if(sm->updated("sensorEvents")){
if(sm->updated("sensorEvents")) {
for (auto event : (*sm)["sensorEvents"].getSensorEvents()) {
if (event.which() == cereal::SensorEventData::ACCELERATION) {
if (auto v = event.getAcceleration().getV(); v.size() >= 3)

View File

@ -145,8 +145,8 @@ int main(int argc, char** argv) {
int counter = 0;
srand (time(NULL));
for (int i = 0; i < 100; i++){
for (int i = 0; i < width * height * 3; i++){
for (int i = 0; i < 100; i++) {
for (int i = 0; i < width * height * 3; i++) {
rgb_frame[i] = (uint8_t)rand();
}

View File

@ -53,7 +53,7 @@ int main() {
if (err < 0) break;
#else
// Just run at 1Hz on apple
while (!do_exit){
while (!do_exit) {
util::sleep_for(1000);
#endif

View File

@ -10,22 +10,22 @@
// We assume that all pins have already been exported on boot,
// and that we have permission to write to them.
int gpio_init(int pin_nr, bool output){
int gpio_init(int pin_nr, bool output) {
char pin_dir_path[50];
int pin_dir_path_len = snprintf(pin_dir_path, sizeof(pin_dir_path),
"/sys/class/gpio/gpio%d/direction", pin_nr);
if(pin_dir_path_len <= 0){
if(pin_dir_path_len <= 0) {
return -1;
}
const char *value = output ? "out" : "in";
return util::write_file(pin_dir_path, (void*)value, strlen(value));
}
int gpio_set(int pin_nr, bool high){
int gpio_set(int pin_nr, bool high) {
char pin_val_path[50];
int pin_val_path_len = snprintf(pin_val_path, sizeof(pin_val_path),
"/sys/class/gpio/gpio%d/value", pin_nr);
if(pin_val_path_len <= 0){
if(pin_val_path_len <= 0) {
return -1;
}
return util::write_file(pin_val_path, (void*)(high ? "1" : "0"), 1);

View File

@ -19,21 +19,21 @@ extern "C" {
#include <i2c/smbus.h>
}
I2CBus::I2CBus(uint8_t bus_id){
I2CBus::I2CBus(uint8_t bus_id) {
char bus_name[20];
snprintf(bus_name, 20, "/dev/i2c-%d", bus_id);
i2c_fd = open(bus_name, O_RDWR);
if(i2c_fd < 0){
if(i2c_fd < 0) {
throw std::runtime_error("Failed to open I2C bus");
}
}
I2CBus::~I2CBus(){
if(i2c_fd >= 0){ close(i2c_fd); }
I2CBus::~I2CBus() {
if(i2c_fd >= 0) { close(i2c_fd); }
}
int I2CBus::read_register(uint8_t device_address, uint register_address, uint8_t *buffer, uint8_t len){
int I2CBus::read_register(uint8_t device_address, uint register_address, uint8_t *buffer, uint8_t len) {
int ret = 0;
ret = ioctl(i2c_fd, I2C_SLAVE, device_address);
@ -46,7 +46,7 @@ fail:
return ret;
}
int I2CBus::set_register(uint8_t device_address, uint register_address, uint8_t data){
int I2CBus::set_register(uint8_t device_address, uint register_address, uint8_t data) {
int ret = 0;
ret = ioctl(i2c_fd, I2C_SLAVE, device_address);
@ -61,14 +61,14 @@ fail:
#else
I2CBus::I2CBus(uint8_t bus_id){
I2CBus::I2CBus(uint8_t bus_id) {
UNUSED(bus_id);
i2c_fd = -1;
}
I2CBus::~I2CBus(){}
I2CBus::~I2CBus() {}
int I2CBus::read_register(uint8_t device_address, uint register_address, uint8_t *buffer, uint8_t len){
int I2CBus::read_register(uint8_t device_address, uint register_address, uint8_t *buffer, uint8_t len) {
UNUSED(device_address);
UNUSED(register_address);
UNUSED(buffer);
@ -76,7 +76,7 @@ int I2CBus::read_register(uint8_t device_address, uint register_address, uint8_t
return -1;
}
int I2CBus::set_register(uint8_t device_address, uint register_address, uint8_t data){
int I2CBus::set_register(uint8_t device_address, uint register_address, uint8_t data) {
UNUSED(device_address);
UNUSED(register_address);
UNUSED(data);

View File

@ -42,9 +42,9 @@ void params_sig_handler(int signal) {
params_do_exit = 1;
}
int fsync_dir(const char* path){
int fsync_dir(const char* path) {
int fd = HANDLE_EINTR(open(path, O_RDONLY, 0755));
if (fd < 0){
if (fd < 0) {
return -1;
}

View File

@ -118,7 +118,7 @@ bool file_exists(const std::string& fn) {
std::string getenv_default(const char* env_var, const char * suffix, const char* default_val) {
const char* env_val = getenv(env_var);
if (env_val != NULL){
if (env_val != NULL) {
return std::string(env_val) + std::string(suffix);
} else {
return std::string(default_val);
@ -155,7 +155,7 @@ std::string dir_name(std::string const &path) {
return path.substr(0, pos);
}
struct tm get_time(){
struct tm get_time() {
time_t rawtime;
time(&rawtime);
@ -165,7 +165,7 @@ struct tm get_time(){
return sys_time;
}
bool time_valid(struct tm sys_time){
bool time_valid(struct tm sys_time) {
int year = 1900 + sys_time.tm_year;
int month = 1 + sys_time.tm_mon;
return (year > 2020) || (year == 2020 && month >= 10);

View File

@ -10,7 +10,7 @@
const std::string watchdog_fn_prefix = "/dev/shm/wd_"; // + <pid>
bool watchdog_kick(){
bool watchdog_kick() {
std::string fn = watchdog_fn_prefix + std::to_string(getpid());
std::string cur_t = std::to_string(nanos_since_boot());

View File

@ -188,11 +188,11 @@ extern "C" {
// out = allocated integer array of size n * (n - 1) / 2 for result
void hclust_pdist(int n, int m, double* pts, double* out) {
int ii = 0;
for (int i = 0; i < n; i++){
for (int j = i + 1; j < n; j++){
for (int i = 0; i < n; i++) {
for (int j = i + 1; j < n; j++) {
// Compute euclidian distance
double d = 0;
for (int k = 0; k < m; k ++){
for (int k = 0; k < m; k ++) {
double error = pts[i * m + k] - pts[j * m + k];
d += (error * error);
}

View File

@ -5,7 +5,7 @@ extern "C" {
}
int main(int argc, const char* argv[]){
int main(int argc, const char* argv[]) {
const int n = 11;
const int m = 3;
double* pts = new double[n*m]{59.26000137, -9.35999966, -5.42500019,
@ -25,7 +25,7 @@ int main(int argc, const char* argv[]){
cluster_points_centroid(n, m, pts, 2.5 * 2.5, idx);
for (int i = 0; i < n; i++){
for (int i = 0; i < n; i++) {
assert(idx[i] == correct_idx[i]);
}

View File

@ -31,7 +31,7 @@ typedef struct {
double cost;
} log_t;
void init(double xCost, double vCost, double aCost, double accelCost, double jerkCost){
void init(double xCost, double vCost, double aCost, double accelCost, double jerkCost) {
acado_initializeSolver();
int i;
const int STEP_MULTIPLIER = 3;
@ -50,7 +50,7 @@ void init(double xCost, double vCost, double aCost, double accelCost, double jer
for (i = 0; i < N; i++) {
int f = 1;
if (i > 4){
if (i > 4) {
f = STEP_MULTIPLIER;
}
// Setup diagonal entries
@ -67,7 +67,7 @@ void init(double xCost, double vCost, double aCost, double accelCost, double jer
}
void init_with_simulation(double v_ego){
void init_with_simulation(double v_ego) {
int i;
double x_ego = 0.0;
@ -75,8 +75,8 @@ void init_with_simulation(double v_ego){
double dt = 0.2;
double t = 0.0;
for (i = 0; i < N + 1; ++i){
if (i > 4){
for (i = 0; i < N + 1; ++i) {
if (i > 4) {
dt = 0.6;
}
@ -95,10 +95,10 @@ void init_with_simulation(double v_ego){
}
int run_mpc(state_t * x0, log_t * solution,
double x_poly[4], double v_poly[4], double a_poly[4]){
double x_poly[4], double v_poly[4], double a_poly[4]) {
int i;
for (i = 0; i < N + 1; ++i){
for (i = 0; i < N + 1; ++i) {
acadoVariables.od[i*NOD+0] = x_poly[0];
acadoVariables.od[i*NOD+1] = x_poly[1];
acadoVariables.od[i*NOD+2] = x_poly[2];
@ -123,13 +123,13 @@ int run_mpc(state_t * x0, log_t * solution,
acado_preparationStep();
acado_feedbackStep();
for (i = 0; i <= N; i++){
for (i = 0; i <= N; i++) {
solution->x_ego[i] = acadoVariables.x[i*NX];
solution->v_ego[i] = acadoVariables.x[i*NX+1];
solution->a_ego[i] = acadoVariables.x[i*NX+2];
solution->t[i] = acadoVariables.x[i*NX+3];
if (i < N){
if (i < N) {
solution->j_ego[i] = acadoVariables.u[i];
}
}

View File

@ -50,7 +50,7 @@ public:
}
static void close_activities() {
if(launched_activity){
if(launched_activity) {
std::system("pm disable com.android.settings && pm enable com.android.settings");
}
}

View File

@ -190,7 +190,7 @@ void Localizer::handle_sensors(double current_time, const capnp::List<cereal::Se
const cereal::SensorEventData::Reader& sensor_reading = log[i];
// Ignore empty readings (e.g. in case the magnetometer had no data ready)
if (sensor_reading.getTimestamp() == 0){
if (sensor_reading.getTimestamp() == 0) {
continue;
}
@ -247,7 +247,7 @@ void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::R
return;
}
if (floatlist2vector(log.getVNED()).norm() > TRANS_SANITY_CHECK){
if (floatlist2vector(log.getVNED()).norm() > TRANS_SANITY_CHECK) {
return;
}
@ -308,7 +308,7 @@ void Localizer::handle_cam_odo(double current_time, const cereal::CameraOdometry
VectorXd rot_calib_std = floatlist2vector(log.getRotStd());
VectorXd trans_calib_std = floatlist2vector(log.getTransStd());
if ((rot_calib_std.minCoeff() <= MIN_STD_SANITY_CHECK) || (trans_calib_std.minCoeff() <= MIN_STD_SANITY_CHECK)){
if ((rot_calib_std.minCoeff() <= MIN_STD_SANITY_CHECK) || (trans_calib_std.minCoeff() <= MIN_STD_SANITY_CHECK)) {
return;
}
@ -334,7 +334,7 @@ void Localizer::handle_cam_odo(double current_time, const cereal::CameraOdometry
void Localizer::handle_live_calib(double current_time, const cereal::LiveCalibrationData::Reader& log) {
if (log.getRpyCalib().size() > 0) {
auto calib = floatlist2vector(log.getRpyCalib());
if ((calib.minCoeff() < -CALIB_RPY_SANITY_CHECK) || (calib.maxCoeff() > CALIB_RPY_SANITY_CHECK)){
if ((calib.minCoeff() < -CALIB_RPY_SANITY_CHECK) || (calib.maxCoeff() > CALIB_RPY_SANITY_CHECK)) {
return;
}
@ -352,7 +352,7 @@ void Localizer::reset_kalman(double current_time) {
void Localizer::finite_check(double current_time) {
bool all_finite = this->kf->get_x().array().isFinite().all() or this->kf->get_P().array().isFinite().all();
if (!all_finite){
if (!all_finite) {
LOGE("Non-finite values detected, kalman reset");
this->reset_kalman(current_time);
}
@ -364,7 +364,7 @@ void Localizer::time_check(double current_time) {
}
double filter_time = this->kf->get_filter_time();
bool big_time_gap = !std::isnan(filter_time) && (current_time - filter_time > 10);
if (big_time_gap){
if (big_time_gap) {
LOGE("Time gap of over 10s detected, kalman reset");
this->reset_kalman(current_time);
}

View File

@ -46,7 +46,7 @@ namespace ublox {
uint32_t tAccNs;
} __attribute__((packed));
inline std::string ubx_add_checksum(const std::string &msg){
inline std::string ubx_add_checksum(const std::string &msg) {
assert(msg.size() > 2);
uint8_t ck_a = 0, ck_b = 0;

View File

@ -25,7 +25,7 @@ int main() {
while (!do_exit) {
Message * msg = subscriber->receive();
if (!msg){
if (!msg) {
if (errno == EINTR) {
do_exit = true;
}

View File

@ -29,7 +29,7 @@ int main(int argc, char *argv[]) {
assert(err >= 0);
// Wait for new message if we didn't receive anything
if (err == 0){
if (err == 0) {
err = sd_journal_wait(journal, 1000 * 1000);
assert (err >= 0);
continue; // Try again
@ -43,12 +43,12 @@ int main(int argc, char *argv[]) {
size_t length;
std::map<std::string, std::string> kv;
SD_JOURNAL_FOREACH_DATA(journal, data, length){
SD_JOURNAL_FOREACH_DATA(journal, data, length) {
std::string str((char*)data, length);
// Split "KEY=VALUE"" on "=" and put in map
std::size_t found = str.find("=");
if (found != std::string::npos){
if (found != std::string::npos) {
kv[str.substr(0, found)] = str.substr(found + 1, std::string::npos);
}
}

View File

@ -172,7 +172,7 @@ void encoder_thread(int cam_idx) {
VisionIpcClient vipc_client = VisionIpcClient("camerad", cam_info.stream_type, false);
while (!do_exit) {
if (!vipc_client.connect(false)){
if (!vipc_client.connect(false)) {
util::sleep_for(100);
continue;
}
@ -198,7 +198,7 @@ void encoder_thread(int cam_idx) {
while (!do_exit) {
VisionIpcBufExtra extra;
VisionBuf* buf = vipc_client.recv(&extra);
if (buf == nullptr){
if (buf == nullptr) {
continue;
}
@ -381,7 +381,7 @@ int main(int argc, char** argv) {
Message * last_msg = nullptr;
while (!do_exit) {
Message * msg = sock->receive(true);
if (!msg){
if (!msg) {
break;
}
delete last_msg;
@ -469,7 +469,7 @@ int main(int argc, char** argv) {
LOGW("closing logger");
logger_close(&s.logger, &do_exit);
if (do_exit.power_failure){
if (do_exit.power_failure) {
LOGE("power failure");
sync();
}

View File

@ -42,10 +42,10 @@ void calibration_thread(bool wide_camera) {
while (!do_exit) {
sm.update(100);
if(sm.updated("liveCalibration")){
if(sm.updated("liveCalibration")) {
auto extrinsic_matrix = sm["liveCalibration"].getLiveCalibration().getExtrinsicMatrix();
Eigen::Matrix<float, 3, 4> extrinsic_matrix_eigen;
for (int i = 0; i < 4*3; i++){
for (int i = 0; i < 4*3; i++) {
extrinsic_matrix_eigen(i / 4, i % 4) = extrinsic_matrix[i];
}

View File

@ -168,7 +168,7 @@ DMonitoringResult dmonitoring_eval_frame(DMonitoringModelState* s, void* stream_
return ret;
}
void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringResult &res, float execution_time, kj::ArrayPtr<const float> raw_pred){
void dmonitoring_publish(PubMaster &pm, uint32_t frame_id, const DMonitoringResult &res, float execution_time, kj::ArrayPtr<const float> raw_pred) {
// make msg
MessageBuilder msg;
auto framed = msg.initEvent().initDriverState();

View File

@ -7,7 +7,7 @@
Eigen::Matrix<float, MODEL_PATH_DISTANCE, POLYFIT_DEGREE> vander;
void poly_init(){
void poly_init() {
// Build Vandermonde matrix
for(int i = 0; i < MODEL_PATH_DISTANCE; i++) {
for(int j = 0; j < POLYFIT_DEGREE; j++) {

View File

@ -7,17 +7,17 @@
BMX055_Accel::BMX055_Accel(I2CBus *bus) : I2CSensor(bus) {}
int BMX055_Accel::init(){
int BMX055_Accel::init() {
int ret = 0;
uint8_t buffer[1];
ret = read_register(BMX055_ACCEL_I2C_REG_ID, buffer, 1);
if(ret < 0){
if(ret < 0) {
LOGE("Reading chip ID failed: %d", ret);
goto fail;
}
if(buffer[0] != BMX055_ACCEL_CHIP_ID){
if(buffer[0] != BMX055_ACCEL_CHIP_ID) {
LOGE("Chip ID wrong. Got: %d, Expected %d", buffer[0], BMX055_ACCEL_CHIP_ID);
ret = -1;
goto fail;
@ -25,17 +25,17 @@ int BMX055_Accel::init(){
// High bandwidth
// ret = set_register(BMX055_ACCEL_I2C_REG_HBW, BMX055_ACCEL_HBW_ENABLE);
// if (ret < 0){
// if (ret < 0) {
// goto fail;
// }
// Low bandwidth
ret = set_register(BMX055_ACCEL_I2C_REG_HBW, BMX055_ACCEL_HBW_DISABLE);
if (ret < 0){
if (ret < 0) {
goto fail;
}
ret = set_register(BMX055_ACCEL_I2C_REG_BW, BMX055_ACCEL_BW_125HZ);
if (ret < 0){
if (ret < 0) {
goto fail;
}
@ -43,7 +43,7 @@ fail:
return ret;
}
void BMX055_Accel::get_event(cereal::SensorEventData::Builder &event){
void BMX055_Accel::get_event(cereal::SensorEventData::Builder &event) {
uint64_t start_time = nanos_since_boot();
uint8_t buffer[6];
int len = read_register(BMX055_ACCEL_I2C_REG_X_LSB, buffer, sizeof(buffer));

View File

@ -10,17 +10,17 @@
BMX055_Gyro::BMX055_Gyro(I2CBus *bus) : I2CSensor(bus) {}
int BMX055_Gyro::init(){
int BMX055_Gyro::init() {
int ret = 0;
uint8_t buffer[1];
ret =read_register(BMX055_GYRO_I2C_REG_ID, buffer, 1);
if(ret < 0){
if(ret < 0) {
LOGE("Reading chip ID failed: %d", ret);
goto fail;
}
if(buffer[0] != BMX055_GYRO_CHIP_ID){
if(buffer[0] != BMX055_GYRO_CHIP_ID) {
LOGE("Chip ID wrong. Got: %d, Expected %d", buffer[0], BMX055_GYRO_CHIP_ID);
ret = -1;
goto fail;
@ -28,25 +28,25 @@ int BMX055_Gyro::init(){
// High bandwidth
// ret = set_register(BMX055_GYRO_I2C_REG_HBW, BMX055_GYRO_HBW_ENABLE);
// if (ret < 0){
// if (ret < 0) {
// goto fail;
// }
// Low bandwidth
ret = set_register(BMX055_GYRO_I2C_REG_HBW, BMX055_GYRO_HBW_DISABLE);
if (ret < 0){
if (ret < 0) {
goto fail;
}
// 116 Hz filter
ret = set_register(BMX055_GYRO_I2C_REG_BW, BMX055_GYRO_BW_116HZ);
if (ret < 0){
if (ret < 0) {
goto fail;
}
// +- 125 deg/s range
ret = set_register(BMX055_GYRO_I2C_REG_RANGE, BMX055_GYRO_RANGE_125);
if (ret < 0){
if (ret < 0) {
goto fail;
}
@ -54,7 +54,7 @@ fail:
return ret;
}
void BMX055_Gyro::get_event(cereal::SensorEventData::Builder &event){
void BMX055_Gyro::get_event(cereal::SensorEventData::Builder &event) {
uint64_t start_time = nanos_since_boot();
uint8_t buffer[6];
int len = read_register(BMX055_GYRO_I2C_REG_RATE_X_LSB, buffer, sizeof(buffer));

View File

@ -65,7 +65,7 @@ static int16_t compensate_z(trim_data_t trim_data, int16_t mag_data_z, uint16_t
BMX055_Magn::BMX055_Magn(I2CBus *bus) : I2CSensor(bus) {}
int BMX055_Magn::init(){
int BMX055_Magn::init() {
int ret;
uint8_t buffer[1];
uint8_t trim_x1y1[2] = {0};
@ -79,7 +79,7 @@ int BMX055_Magn::init(){
// suspend -> sleep
ret = set_register(BMX055_MAGN_I2C_REG_PWR_0, 0x01);
if(ret < 0){
if(ret < 0) {
LOGE("Enabling power failed: %d", ret);
goto fail;
}
@ -87,12 +87,12 @@ int BMX055_Magn::init(){
// read chip ID
ret = read_register(BMX055_MAGN_I2C_REG_ID, buffer, 1);
if(ret < 0){
if(ret < 0) {
LOGE("Reading chip ID failed: %d", ret);
goto fail;
}
if(buffer[0] != BMX055_MAGN_CHIP_ID){
if(buffer[0] != BMX055_MAGN_CHIP_ID) {
LOGE("Chip ID wrong. Got: %d, Expected %d", buffer[0], BMX055_MAGN_CHIP_ID);
return -1;
}
@ -139,12 +139,12 @@ int BMX055_Magn::init(){
// Chose NXY = 7, NZ = 12, which gives 125 Hz,
// and has the same ratio as the high accuracy preset
ret = set_register(BMX055_MAGN_I2C_REG_REPXY, (7 - 1) / 2);
if (ret < 0){
if (ret < 0) {
goto fail;
}
ret = set_register(BMX055_MAGN_I2C_REG_REPZ, 12 - 1);
if (ret < 0){
if (ret < 0) {
goto fail;
}
@ -155,7 +155,7 @@ int BMX055_Magn::init(){
return ret;
}
bool BMX055_Magn::perform_self_test(){
bool BMX055_Magn::perform_self_test() {
uint8_t buffer[8];
int16_t x, y;
int16_t neg_z, pos_z;
@ -189,16 +189,16 @@ bool BMX055_Magn::perform_self_test(){
int16_t diff = pos_z - neg_z;
bool passed = (diff > 180) && (diff < 240);
if (!passed){
if (!passed) {
LOGE("self test failed: neg %d pos %d diff %d", neg_z, pos_z, diff);
}
return passed;
}
bool BMX055_Magn::parse_xyz(uint8_t buffer[8], int16_t *x, int16_t *y, int16_t *z){
bool BMX055_Magn::parse_xyz(uint8_t buffer[8], int16_t *x, int16_t *y, int16_t *z) {
bool ready = buffer[6] & 0x1;
if (ready){
if (ready) {
int16_t mdata_x = (int16_t) (((int16_t)buffer[1] << 8) | buffer[0]) >> 3;
int16_t mdata_y = (int16_t) (((int16_t)buffer[3] << 8) | buffer[2]) >> 3;
int16_t mdata_z = (int16_t) (((int16_t)buffer[5] << 8) | buffer[4]) >> 1;
@ -213,7 +213,7 @@ bool BMX055_Magn::parse_xyz(uint8_t buffer[8], int16_t *x, int16_t *y, int16_t *
}
void BMX055_Magn::get_event(cereal::SensorEventData::Builder &event){
void BMX055_Magn::get_event(cereal::SensorEventData::Builder &event) {
uint64_t start_time = nanos_since_boot();
uint8_t buffer[8];
int16_t _x, _y, x, y, z;
@ -221,7 +221,7 @@ void BMX055_Magn::get_event(cereal::SensorEventData::Builder &event){
int len = read_register(BMX055_MAGN_I2C_REG_DATAX_LSB, buffer, sizeof(buffer));
assert(len == sizeof(buffer));
if (parse_xyz(buffer, &_x, &_y, &z)){
if (parse_xyz(buffer, &_x, &_y, &z)) {
event.setSource(cereal::SensorEventData::SensorSource::BMX055);
event.setVersion(2);
event.setSensor(SENSOR_MAGNETOMETER_UNCALIBRATED);

View File

@ -8,17 +8,17 @@
BMX055_Temp::BMX055_Temp(I2CBus *bus) : I2CSensor(bus) {}
int BMX055_Temp::init(){
int BMX055_Temp::init() {
int ret = 0;
uint8_t buffer[1];
ret = read_register(BMX055_ACCEL_I2C_REG_ID, buffer, 1);
if(ret < 0){
if(ret < 0) {
LOGE("Reading chip ID failed: %d", ret);
goto fail;
}
if(buffer[0] != BMX055_ACCEL_CHIP_ID){
if(buffer[0] != BMX055_ACCEL_CHIP_ID) {
LOGE("Chip ID wrong. Got: %d, Expected %d", buffer[0], BMX055_ACCEL_CHIP_ID);
ret = -1;
goto fail;
@ -28,7 +28,7 @@ fail:
return ret;
}
void BMX055_Temp::get_event(cereal::SensorEventData::Builder &event){
void BMX055_Temp::get_event(cereal::SensorEventData::Builder &event) {
uint64_t start_time = nanos_since_boot();
uint8_t buffer[1];
int len = read_register(BMX055_ACCEL_I2C_REG_TEMP, buffer, sizeof(buffer));

View File

@ -9,6 +9,6 @@ int FileSensor::init() {
return file.is_open() ? 0 : 1;
}
FileSensor::~FileSensor(){
FileSensor::~FileSensor() {
file.close();
}

View File

@ -1,23 +1,23 @@
#include "i2c_sensor.h"
int16_t read_12_bit(uint8_t lsb, uint8_t msb){
int16_t read_12_bit(uint8_t lsb, uint8_t msb) {
uint16_t combined = (uint16_t(msb) << 8) | uint16_t(lsb & 0xF0);
return int16_t(combined) / (1 << 4);
}
int16_t read_16_bit(uint8_t lsb, uint8_t msb){
int16_t read_16_bit(uint8_t lsb, uint8_t msb) {
uint16_t combined = (uint16_t(msb) << 8) | uint16_t(lsb);
return int16_t(combined);
}
I2CSensor::I2CSensor(I2CBus *bus) : bus(bus){
I2CSensor::I2CSensor(I2CBus *bus) : bus(bus) {
}
int I2CSensor::read_register(uint register_address, uint8_t *buffer, uint8_t len){
int I2CSensor::read_register(uint register_address, uint8_t *buffer, uint8_t len) {
return bus->read_register(get_device_address(), register_address, buffer, len);
}
int I2CSensor::set_register(uint register_address, uint8_t data){
int I2CSensor::set_register(uint register_address, uint8_t data) {
return bus->set_register(get_device_address(), register_address, data);
}

View File

@ -5,7 +5,7 @@
#include "selfdrive/common/timing.h"
#include "selfdrive/sensord/sensors/constants.h"
void LightSensor::get_event(cereal::SensorEventData::Builder &event){
void LightSensor::get_event(cereal::SensorEventData::Builder &event) {
uint64_t start_time = nanos_since_boot();
file.clear();
file.seekg(0);

View File

@ -7,17 +7,17 @@
LSM6DS3_Accel::LSM6DS3_Accel(I2CBus *bus) : I2CSensor(bus) {}
int LSM6DS3_Accel::init(){
int LSM6DS3_Accel::init() {
int ret = 0;
uint8_t buffer[1];
ret = read_register(LSM6DS3_ACCEL_I2C_REG_ID, buffer, 1);
if(ret < 0){
if(ret < 0) {
LOGE("Reading chip ID failed: %d", ret);
goto fail;
}
if(buffer[0] != LSM6DS3_ACCEL_CHIP_ID){
if(buffer[0] != LSM6DS3_ACCEL_CHIP_ID) {
LOGE("Chip ID wrong. Got: %d, Expected %d", buffer[0], LSM6DS3_ACCEL_CHIP_ID);
ret = -1;
goto fail;
@ -25,7 +25,7 @@ int LSM6DS3_Accel::init(){
// TODO: set scale and bandwith. Default is +- 2G, 50 Hz
ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL1_XL, LSM6DS3_ACCEL_ODR_104HZ);
if (ret < 0){
if (ret < 0) {
goto fail;
}
@ -34,7 +34,7 @@ fail:
return ret;
}
void LSM6DS3_Accel::get_event(cereal::SensorEventData::Builder &event){
void LSM6DS3_Accel::get_event(cereal::SensorEventData::Builder &event) {
uint64_t start_time = nanos_since_boot();
uint8_t buffer[6];

View File

@ -11,17 +11,17 @@
LSM6DS3_Gyro::LSM6DS3_Gyro(I2CBus *bus) : I2CSensor(bus) {}
int LSM6DS3_Gyro::init(){
int LSM6DS3_Gyro::init() {
int ret = 0;
uint8_t buffer[1];
ret = read_register(LSM6DS3_GYRO_I2C_REG_ID, buffer, 1);
if(ret < 0){
if(ret < 0) {
LOGE("Reading chip ID failed: %d", ret);
goto fail;
}
if(buffer[0] != LSM6DS3_GYRO_CHIP_ID){
if(buffer[0] != LSM6DS3_GYRO_CHIP_ID) {
LOGE("Chip ID wrong. Got: %d, Expected %d", buffer[0], LSM6DS3_GYRO_CHIP_ID);
ret = -1;
goto fail;
@ -29,7 +29,7 @@ int LSM6DS3_Gyro::init(){
// TODO: set scale. Default is +- 250 deg/s
ret = set_register(LSM6DS3_GYRO_I2C_REG_CTRL2_G, LSM6DS3_GYRO_ODR_104HZ);
if (ret < 0){
if (ret < 0) {
goto fail;
}
@ -38,7 +38,7 @@ fail:
return ret;
}
void LSM6DS3_Gyro::get_event(cereal::SensorEventData::Builder &event){
void LSM6DS3_Gyro::get_event(cereal::SensorEventData::Builder &event) {
uint64_t start_time = nanos_since_boot();
uint8_t buffer[6];

View File

@ -7,17 +7,17 @@
LSM6DS3_Temp::LSM6DS3_Temp(I2CBus *bus) : I2CSensor(bus) {}
int LSM6DS3_Temp::init(){
int LSM6DS3_Temp::init() {
int ret = 0;
uint8_t buffer[1];
ret = read_register(LSM6DS3_TEMP_I2C_REG_ID, buffer, 1);
if(ret < 0){
if(ret < 0) {
LOGE("Reading chip ID failed: %d", ret);
goto fail;
}
if(buffer[0] != LSM6DS3_TEMP_CHIP_ID){
if(buffer[0] != LSM6DS3_TEMP_CHIP_ID) {
LOGE("Chip ID wrong. Got: %d, Expected %d", buffer[0], LSM6DS3_TEMP_CHIP_ID);
ret = -1;
goto fail;
@ -27,7 +27,7 @@ fail:
return ret;
}
void LSM6DS3_Temp::get_event(cereal::SensorEventData::Builder &event){
void LSM6DS3_Temp::get_event(cereal::SensorEventData::Builder &event) {
uint64_t start_time = nanos_since_boot();
uint8_t buffer[2];

View File

@ -189,7 +189,7 @@ void sensor_loop() {
pm.send("sensorEvents", msg);
if (re_init_sensors){
if (re_init_sensors) {
LOGE("Resetting sensors");
re_init_sensors = false;
break;

View File

@ -59,9 +59,9 @@ int sensor_loop() {
sensors.push_back(&light);
for (Sensor * sensor : sensors){
for (Sensor * sensor : sensors) {
int err = sensor->init();
if (err < 0){
if (err < 0) {
LOGE("Error initializing sensors");
return -1;
}
@ -69,14 +69,14 @@ int sensor_loop() {
PubMaster pm({"sensorEvents"});
while (!do_exit){
while (!do_exit) {
std::chrono::steady_clock::time_point begin = std::chrono::steady_clock::now();
const int num_events = sensors.size();
MessageBuilder msg;
auto sensor_events = msg.initEvent().initSensorEvents(num_events);
for (int i = 0; i < num_events; i++){
for (int i = 0; i < num_events; i++) {
auto event = sensor_events[i];
sensors[i]->get_event(event);
}

View File

@ -434,7 +434,7 @@ void ui_nvg_init(UIState *s) {
ui_resize(s, s->fb_w, s->fb_h);
}
void ui_resize(UIState *s, int width, int height){
void ui_resize(UIState *s, int width, int height) {
s->fb_w = width;
s->fb_h = height;

View File

@ -90,7 +90,7 @@ HttpRequest::HttpRequest(QObject *parent, const QString &requestURL, const QStri
}
}
void HttpRequest::sendRequest(const QString &requestURL){
void HttpRequest::sendRequest(const QString &requestURL) {
QString token;
if(create_jwt) {
token = CommaApi::create_jwt();
@ -110,12 +110,12 @@ void HttpRequest::sendRequest(const QString &requestURL){
connect(reply, &QNetworkReply::finished, this, &HttpRequest::requestFinished);
}
void HttpRequest::requestTimeout(){
void HttpRequest::requestTimeout() {
reply->abort();
}
// This function should always emit something
void HttpRequest::requestFinished(){
void HttpRequest::requestFinished() {
if (reply->error() != QNetworkReply::OperationCanceledError) {
networkTimer->stop();
QString response = reply->readAll();

View File

@ -72,7 +72,7 @@ void HomeWindow::mousePressEvent(QMouseEvent* e) {
// TODO: Handle this without exposing pointer to map widget
// Hide map first if visible, then hide sidebar
if (onroad->map != nullptr && onroad->map->isVisible()){
if (onroad->map != nullptr && onroad->map->isVisible()) {
onroad->map->setVisible(false);
} else if (!sidebar->isVisible()) {
sidebar->setVisible(true);

View File

@ -22,7 +22,7 @@ const float MAP_SCALE = 2;
MapWindow::MapWindow(const QMapboxGLSettings &settings) : m_settings(settings) {
if (DRAW_MODEL_PATH){
if (DRAW_MODEL_PATH) {
sm = new SubMaster({"liveLocationKalman", "modelV2"});
} else {
sm = new SubMaster({"liveLocationKalman"});
@ -55,7 +55,7 @@ MapWindow::MapWindow(const QMapboxGLSettings &settings) : m_settings(settings) {
geoservice_provider = new QGeoServiceProvider("mapbox", parameters);
routing_manager = geoservice_provider->routingManager();
if (routing_manager == nullptr){
if (routing_manager == nullptr) {
qDebug() << geoservice_provider->errorString();
assert(routing_manager);
}
@ -76,7 +76,7 @@ MapWindow::~MapWindow() {
void MapWindow::initLayers() {
// This doesn't work from initializeGL
if (!m_map->layerExists("modelPathLayer")){
if (!m_map->layerExists("modelPathLayer")) {
QVariantMap modelPath;
modelPath["id"] = "modelPathLayer";
modelPath["type"] = "line";
@ -86,7 +86,7 @@ void MapWindow::initLayers() {
m_map->setPaintProperty("modelPathLayer", "line-width", 5.0);
m_map->setLayoutProperty("modelPathLayer", "line-cap", "round");
}
if (!m_map->layerExists("navLayer")){
if (!m_map->layerExists("navLayer")) {
QVariantMap nav;
nav["id"] = "navLayer";
nav["type"] = "line";
@ -96,7 +96,7 @@ void MapWindow::initLayers() {
m_map->setPaintProperty("navLayer", "line-width", 7.5);
m_map->setLayoutProperty("navLayer", "line-cap", "round");
}
if (!m_map->layerExists("carPosLayer")){
if (!m_map->layerExists("carPosLayer")) {
m_map->addImage("label-arrow", QImage("../assets/images/triangle.svg"));
QVariantMap carPos;
@ -133,14 +133,14 @@ void MapWindow::timerUpdate() {
last_position = coordinate;
last_bearing = bearing;
if (pan_counter == 0){
if (pan_counter == 0) {
m_map->setCoordinate(coordinate);
m_map->setBearing(bearing);
} else {
pan_counter--;
}
if (zoom_counter == 0){
if (zoom_counter == 0) {
static FirstOrderFilter velocity_filter(velocity, 10, 0.1);
m_map->setZoom(util::map_val<float>(velocity_filter.update(velocity), 0, 30, MAX_ZOOM, MIN_ZOOM));
} else {
@ -171,7 +171,7 @@ void MapWindow::timerUpdate() {
if (segment.isValid()) {
auto cur_maneuver = segment.maneuver();
auto attrs = cur_maneuver.extendedAttributes();
if (cur_maneuver.isValid() && attrs.contains("mapbox.banner_instructions")){
if (cur_maneuver.isValid() && attrs.contains("mapbox.banner_instructions")) {
float along_geometry = distance_along_geometry(segment.path(), to_QGeoCoordinate(last_position));
float distance = std::max(0.0f, float(segment.distance()) - along_geometry);
emit distanceChanged(distance);
@ -179,7 +179,7 @@ void MapWindow::timerUpdate() {
m_map->setPitch(MAX_PITCH); // TODO: smooth pitching based on maneuver distance
auto banner = attrs["mapbox.banner_instructions"].toList();
if (banner.size()){
if (banner.size()) {
map_instructions->setVisible(true);
auto banner_0 = banner[0].toMap();
@ -189,12 +189,12 @@ void MapWindow::timerUpdate() {
}
auto next_segment = segment.nextRouteSegment();
if (next_segment.isValid()){
if (next_segment.isValid()) {
auto next_maneuver = next_segment.maneuver();
if (next_maneuver.isValid()){
if (next_maneuver.isValid()) {
float next_maneuver_distance = next_maneuver.position().distanceTo(to_QGeoCoordinate(last_position));
// Switch to next route segment
if (next_maneuver_distance < REROUTE_DISTANCE && next_maneuver_distance > last_maneuver_distance){
if (next_maneuver_distance < REROUTE_DISTANCE && next_maneuver_distance > last_maneuver_distance) {
segment = next_segment;
recompute_backoff = std::max(0, recompute_backoff - 1);
@ -217,7 +217,7 @@ void MapWindow::timerUpdate() {
update();
if (!segment.isValid()){
if (!segment.isValid()) {
map_instructions->setVisible(false);
}
@ -247,7 +247,7 @@ void MapWindow::paintGL() {
m_map->render();
}
static float get_time_typical(const QGeoRouteSegment &segment){
static float get_time_typical(const QGeoRouteSegment &segment) {
auto maneuver = segment.maneuver();
auto attrs = maneuver.extendedAttributes();
return attrs.contains("mapbox.duration_typical") ? attrs["mapbox.duration_typical"].toDouble() : segment.travelTime();
@ -263,7 +263,7 @@ void MapWindow::recomputeRoute() {
return;
}
if (*new_destination != nav_destination){
if (*new_destination != nav_destination) {
setVisible(true); // Show map on destination set/change
should_recompute = true;
}
@ -354,8 +354,8 @@ void MapWindow::clearRoute() {
}
bool MapWindow::shouldRecompute(){
if (!segment.isValid()){
bool MapWindow::shouldRecompute() {
if (!segment.isValid()) {
return true;
}
@ -363,7 +363,7 @@ bool MapWindow::shouldRecompute(){
float min_d = REROUTE_DISTANCE + 1;
auto path = segment.path();
auto cur = to_QGeoCoordinate(last_position);
for (size_t i = 0; i < path.size() - 1; i++){
for (size_t i = 0; i < path.size() - 1; i++) {
auto a = path[i];
auto b = path[i+1];
if (a.distanceTo(b) < 1.0) {
@ -381,7 +381,7 @@ void MapWindow::mousePressEvent(QMouseEvent *ev) {
ev->accept();
}
void MapWindow::mouseMoveEvent(QMouseEvent *ev){
void MapWindow::mouseMoveEvent(QMouseEvent *ev) {
QPointF delta = ev->localPos() - m_lastPos;
if (!delta.isNull()) {
@ -409,7 +409,7 @@ void MapWindow::wheelEvent(QWheelEvent *ev) {
}
bool MapWindow::event(QEvent *event) {
if (event->type() == QEvent::Gesture){
if (event->type() == QEvent::Gesture) {
return gestureEvent(static_cast<QGestureEvent*>(event));
}
@ -417,7 +417,7 @@ bool MapWindow::event(QEvent *event) {
}
bool MapWindow::gestureEvent(QGestureEvent *event) {
if (QGesture *pinch = event->gesture(Qt::PinchGesture)){
if (QGesture *pinch = event->gesture(Qt::PinchGesture)) {
pinchTriggered(static_cast<QPinchGesture *>(pinch));
}
return true;
@ -440,7 +440,7 @@ void MapWindow::offroadTransition(bool offroad) {
last_bearing = {};
}
MapInstructions::MapInstructions(QWidget * parent) : QWidget(parent){
MapInstructions::MapInstructions(QWidget * parent) : QWidget(parent) {
QHBoxLayout *layout_outer = new QHBoxLayout;
layout_outer->setContentsMargins(11, 50, 11, 11);
{
@ -490,7 +490,7 @@ MapInstructions::MapInstructions(QWidget * parent) : QWidget(parent){
setPalette(pal);
}
void MapInstructions::updateDistance(float d){
void MapInstructions::updateDistance(float d) {
QString distance_str;
if (QUIState::ui_state.scene.is_metric) {
@ -517,7 +517,7 @@ void MapInstructions::updateDistance(float d){
distance->setText(distance_str);
}
void MapInstructions::updateInstructions(QMap<QString, QVariant> banner, bool full){
void MapInstructions::updateInstructions(QMap<QString, QVariant> banner, bool full) {
// Need multiple calls to adjustSize for it to properly resize
// seems like it takes a little bit of time for the images to change and
// the size can only be changed afterwards
@ -530,9 +530,9 @@ void MapInstructions::updateInstructions(QMap<QString, QVariant> banner, bool fu
primary_str += p["text"].toString();
// Show arrow with direction
if (p.contains("type")){
if (p.contains("type")) {
QString fn = "../assets/navigation/direction_" + p["type"].toString();
if (p.contains("modifier")){
if (p.contains("modifier")) {
fn += "_" + p["modifier"].toString();
}
fn += + ".png";
@ -548,12 +548,12 @@ void MapInstructions::updateInstructions(QMap<QString, QVariant> banner, bool fu
QString icon_fn;
for (auto &c : components) {
auto cc = c.toMap();
if (cc["type"].toString() == "icon"){
if (cc["type"].toString() == "icon") {
icon_fn = cc["imageBaseURL"].toString() + "@3x.png";
}
}
if (banner.contains("secondary") && full){
if (banner.contains("secondary") && full) {
auto s = banner["secondary"].toMap();
secondary_str += s["text"].toString();
}
@ -561,12 +561,12 @@ void MapInstructions::updateInstructions(QMap<QString, QVariant> banner, bool fu
clearLayout(lane_layout);
bool has_lanes = false;
if (banner.contains("sub") && full){
if (banner.contains("sub") && full) {
auto s = banner["sub"].toMap();
auto components = s["components"].toList();
for (auto &c : components) {
auto cc = c.toMap();
if (cc["type"].toString() == "lane"){
if (cc["type"].toString() == "lane") {
has_lanes = true;
bool left = false;
@ -574,7 +574,7 @@ void MapInstructions::updateInstructions(QMap<QString, QVariant> banner, bool fu
bool right = false;
bool active = cc["active"].toBool();
for (auto &dir : cc["directions"].toList()){
for (auto &dir : cc["directions"].toList()) {
auto d = dir.toString();
left |= d.contains("left");
straight |= d.contains("straight");
@ -585,7 +585,7 @@ void MapInstructions::updateInstructions(QMap<QString, QVariant> banner, bool fu
QString fn = "../assets/navigation/direction_";
if (left) {
fn += "turn_left";
} else if (right){
} else if (right) {
fn += "turn_right";
} else if (straight) {
fn += "turn_straight";
@ -607,7 +607,7 @@ void MapInstructions::updateInstructions(QMap<QString, QVariant> banner, bool fu
last_banner = banner;
}
MapETA::MapETA(QWidget * parent) : QWidget(parent){
MapETA::MapETA(QWidget * parent) : QWidget(parent) {
QHBoxLayout *layout_outer = new QHBoxLayout;
layout_outer->setContentsMargins(20, 25, 20, 25);

View File

@ -23,7 +23,7 @@ QMapbox::CoordinatesCollections model_to_collection(
auto x = line.getX();
auto y = line.getY();
auto z = line.getZ();
for (int i = 0; i < x.size(); i++){
for (int i = 0; i < x.size(); i++) {
Eigen::Vector3d point_ecef = ecef_from_local * Eigen::Vector3d(x[i], y[i], z[i]) + ecef;
Geodetic point_geodetic = ecef2geodetic((ECEF){.x = point_ecef[0], .y = point_ecef[1], .z = point_ecef[2]});
QMapbox::Coordinate coordinate(point_geodetic.lat, point_geodetic.lon);
@ -38,7 +38,7 @@ QMapbox::CoordinatesCollections model_to_collection(
return collections;
}
QMapbox::CoordinatesCollections coordinate_to_collection(QMapbox::Coordinate c){
QMapbox::CoordinatesCollections coordinate_to_collection(QMapbox::Coordinate c) {
QMapbox::Coordinates coordinates;
coordinates.push_back(c);
@ -53,7 +53,7 @@ QMapbox::CoordinatesCollections coordinate_to_collection(QMapbox::Coordinate c){
QMapbox::CoordinatesCollections coordinate_list_to_collection(QList<QGeoCoordinate> coordinate_list) {
QMapbox::Coordinates coordinates;
for (auto &c : coordinate_list){
for (auto &c : coordinate_list) {
QMapbox::Coordinate coordinate(c.latitude(), c.longitude());
coordinates.push_back(coordinate);
}
@ -66,19 +66,19 @@ QMapbox::CoordinatesCollections coordinate_list_to_collection(QList<QGeoCoordina
return collections;
}
static QGeoCoordinate sub(QGeoCoordinate v, QGeoCoordinate w){
static QGeoCoordinate sub(QGeoCoordinate v, QGeoCoordinate w) {
return QGeoCoordinate(v.latitude() - w.latitude(), v.longitude() - w.longitude());
}
static QGeoCoordinate add(QGeoCoordinate v, QGeoCoordinate w){
static QGeoCoordinate add(QGeoCoordinate v, QGeoCoordinate w) {
return QGeoCoordinate(v.latitude() + w.latitude(), v.longitude() + w.longitude());
}
static QGeoCoordinate mul(QGeoCoordinate v, float c){
static QGeoCoordinate mul(QGeoCoordinate v, float c) {
return QGeoCoordinate(c * v.latitude(), c * v.longitude());
}
static float dot(QGeoCoordinate v, QGeoCoordinate w){
static float dot(QGeoCoordinate v, QGeoCoordinate w) {
return v.latitude() * w.latitude() + v.longitude() * w.longitude();
}
@ -122,7 +122,7 @@ std::optional<QMapbox::Coordinate> coordinate_from_param(std::string param) {
if (doc.isNull()) return {};
QJsonObject json = doc.object();
if (json["latitude"].isDouble() && json["longitude"].isDouble()){
if (json["latitude"].isDouble() && json["longitude"].isDouble()) {
QMapbox::Coordinate coord(json["latitude"].toDouble(), json["longitude"].toDouble());
return coord;
} else {

View File

@ -23,7 +23,7 @@ void NetworkStrengthWidget::paintEvent(QPaintEvent* event) {
// Networking functions
Networking::Networking(QWidget* parent, bool show_advanced) : QWidget(parent), show_advanced(show_advanced){
Networking::Networking(QWidget* parent, bool show_advanced) : QWidget(parent), show_advanced(show_advanced) {
s = new QStackedLayout;
QLabel* warning = new QLabel("Network manager is inactive!");
@ -39,7 +39,7 @@ Networking::Networking(QWidget* parent, bool show_advanced) : QWidget(parent), s
attemptInitialization();
}
void Networking::attemptInitialization(){
void Networking::attemptInitialization() {
// Checks if network manager is active
try {
wifi = new WifiManager(this);
@ -55,7 +55,7 @@ void Networking::attemptInitialization(){
QPushButton* advancedSettings = new QPushButton("Advanced");
advancedSettings->setStyleSheet("margin-right: 30px;");
advancedSettings->setFixedSize(350, 100);
connect(advancedSettings, &QPushButton::released, [=](){ s->setCurrentWidget(an); });
connect(advancedSettings, &QPushButton::released, [=]() { s->setCurrentWidget(an); });
vlayout->addSpacing(10);
vlayout->addWidget(advancedSettings, 0, Qt::AlignRight);
vlayout->addSpacing(10);
@ -70,7 +70,7 @@ void Networking::attemptInitialization(){
s->addWidget(wifiScreen);
an = new AdvancedNetworking(this, wifi);
connect(an, &AdvancedNetworking::backPress, [=](){s->setCurrentWidget(wifiScreen);});
connect(an, &AdvancedNetworking::backPress, [=]() { s->setCurrentWidget(wifiScreen); });
s->addWidget(an);
setStyleSheet(R"(
@ -92,7 +92,7 @@ void Networking::attemptInitialization(){
ui_setup_complete = true;
}
void Networking::refresh(){
void Networking::refresh() {
if (!this->isVisible()) {
return;
}
@ -127,7 +127,7 @@ void Networking::wrongPassword(const QString &ssid) {
// AdvancedNetworking functions
AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWidget(parent), wifi(wifi){
AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWidget(parent), wifi(wifi) {
QVBoxLayout* vlayout = new QVBoxLayout;
vlayout->setMargin(40);
@ -136,7 +136,7 @@ AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWid
// Back button
QPushButton* back = new QPushButton("Back");
back->setFixedSize(500, 100);
connect(back, &QPushButton::released, [=](){emit backPress();});
connect(back, &QPushButton::released, [=]() { emit backPress(); });
vlayout->addWidget(back, 0, Qt::AlignLeft);
// Enable tethering layout
@ -146,7 +146,7 @@ AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWid
vlayout->addWidget(horizontal_line(), 0);
// Change tethering password
editPasswordButton = new ButtonControl("Tethering Password", "EDIT", "", [=](){
editPasswordButton = new ButtonControl("Tethering Password", "EDIT", "", [=]() {
QString pass = InputDialog::getText("Enter new tethering password", 8);
if (pass.size()) {
wifi->changeTetheringPassword(pass);
@ -169,7 +169,7 @@ AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWid
setLayout(vlayout);
}
void AdvancedNetworking::refresh(){
void AdvancedNetworking::refresh() {
ipLabel->setText(wifi->ipv4_address);
update();
}

View File

@ -104,7 +104,7 @@ void TermsPage::showEvent(QShowEvent *event) {
)");
}
void TermsPage::enableAccept(){
void TermsPage::enableAccept() {
accept_btn->setText("Accept");
accept_btn->setEnabled(true);
return;
@ -137,7 +137,7 @@ void DeclinePage::showEvent(QShowEvent *event) {
uninstall_btn->setStyleSheet("background-color: #E22C2C;");
buttons->addWidget(uninstall_btn);
QObject::connect(uninstall_btn, &QPushButton::released, [=](){
QObject::connect(uninstall_btn, &QPushButton::released, [=]() {
if (ConfirmationDialog::confirm("Are you sure you want to uninstall?", this)) {
Params().putBool("DoUninstall", true);
}
@ -174,13 +174,13 @@ OnboardingWindow::OnboardingWindow(QWidget *parent) : QStackedWidget(parent) {
TermsPage* terms = new TermsPage(this);
addWidget(terms);
connect(terms, &TermsPage::acceptedTerms, [=](){
connect(terms, &TermsPage::acceptedTerms, [=]() {
Params().put("HasAcceptedTerms", current_terms_version);
updateActiveScreen();
});
TrainingGuide* tr = new TrainingGuide(this);
connect(tr, &TrainingGuide::completedTraining, [=](){
connect(tr, &TrainingGuide::completedTraining, [=]() {
Params().put("CompletedTrainingVersion", current_training_version);
updateActiveScreen();
});
@ -189,11 +189,11 @@ OnboardingWindow::OnboardingWindow(QWidget *parent) : QStackedWidget(parent) {
DeclinePage* declinePage = new DeclinePage(this);
addWidget(declinePage);
connect(terms, &TermsPage::declinedTerms, [=](){
connect(terms, &TermsPage::declinedTerms, [=]() {
setCurrentIndex(2);
});
connect(declinePage, &DeclinePage::getBack, [=](){
connect(declinePage, &DeclinePage::getBack, [=]() {
updateActiveScreen();
});

View File

@ -92,8 +92,8 @@ TogglesPanel::TogglesPanel(QWidget *parent) : QWidget(parent) {
bool record_lock = Params().getBool("RecordFrontLock");
record_toggle->setEnabled(!record_lock);
for(ParamControl *toggle : toggles){
if(toggles_list->count() != 0){
for(ParamControl *toggle : toggles) {
if(toggles_list->count() != 0) {
toggles_list->addWidget(horizontal_line());
}
toggles_list->addWidget(toggle);
@ -164,7 +164,7 @@ DevicePanel::DevicePanel(QWidget* parent) : QWidget(parent) {
}
}, "", this));
for(auto &btn : offroad_btns){
for(auto &btn : offroad_btns) {
device_layout->addWidget(horizontal_line());
QObject::connect(parent, SIGNAL(offroadTransition(bool)), btn, SLOT(setEnabled(bool)));
device_layout->addWidget(btn);
@ -240,7 +240,7 @@ void SoftwarePanel::updateLabels() {
QString lastUpdateTime = "";
std::string last_update_param = params.get("LastUpdateTime");
if (!last_update_param.empty()){
if (!last_update_param.empty()) {
QDateTime lastUpdateDate = QDateTime::fromString(QString::fromStdString(last_update_param + "Z"), Qt::ISODate);
lastUpdateTime = timeAgo(lastUpdateDate);
}
@ -363,7 +363,7 @@ SettingsWindow::SettingsWindow(QWidget *parent) : QFrame(parent) {
};
#ifdef ENABLE_MAPS
if (!Params().get("MapboxToken").empty()){
if (!Params().get("MapboxToken").empty()) {
panels.push_back({"Navigation", new MapPanel(this)});
}
#endif
@ -424,15 +424,15 @@ SettingsWindow::SettingsWindow(QWidget *parent) : QFrame(parent) {
)");
}
void SettingsWindow::hideEvent(QHideEvent *event){
void SettingsWindow::hideEvent(QHideEvent *event) {
#ifdef QCOM
HardwareEon::close_activities();
#endif
// TODO: this should be handled by the Dialog classes
QList<QWidget*> children = findChildren<QWidget *>();
for(auto &w : children){
if(w->metaObject()->superClass()->className() == QString("QDialog")){
for(auto &w : children) {
if(w->metaObject()->superClass()->className() == QString("QDialog")) {
w->close();
}
}

View File

@ -70,7 +70,7 @@ WifiManager::WifiManager(QWidget* parent) : QWidget(parent) {
adapter = get_adapter();
bool has_adapter = adapter != "";
if (!has_adapter){
if (!has_adapter) {
throw std::runtime_error("Error connecting to NetworkManager");
}
@ -110,12 +110,12 @@ void WifiManager::refreshNetworks() {
}
QString WifiManager::get_ipv4_address(){
if (raw_adapter_state != state_connected){
QString WifiManager::get_ipv4_address() {
if (raw_adapter_state != state_connected) {
return "";
}
QVector<QDBusObjectPath> conns = get_active_connections();
for (auto &p : conns){
for (auto &p : conns) {
QString active_connection = p.path();
QDBusInterface nm(nm_service, active_connection, props_iface, bus);
nm.setTimeout(dbus_timeout);
@ -132,7 +132,7 @@ QString WifiManager::get_ipv4_address(){
const QDBusArgument &arr = get_response<QDBusArgument>(nm2.call("Get", ipv4config_iface, "AddressData"));
QMap<QString, QVariant> pth2;
arr.beginArray();
while (!arr.atEnd()){
while (!arr.atEnd()) {
arr >> pth2;
QString ipv4 = pth2.value("address").value<QString>();
arr.endArray();
@ -280,7 +280,7 @@ QVector<QDBusObjectPath> WifiManager::get_active_connections() {
}
void WifiManager::clear_connections(const QString &ssid) {
for(QDBusObjectPath path : list_connections()){
for(QDBusObjectPath path : list_connections()) {
QDBusInterface nm2(nm_service, path.path(), nm_settings_conn_iface, bus);
nm2.setTimeout(dbus_timeout);
@ -392,7 +392,7 @@ void WifiManager::disconnect() {
}
}
QVector<QDBusObjectPath> WifiManager::list_connections(){
QVector<QDBusObjectPath> WifiManager::list_connections() {
QVector<QDBusObjectPath> connections;
QDBusInterface nm(nm_service, nm_settings_path, nm_settings_iface, bus);
nm.setTimeout(dbus_timeout);
@ -409,10 +409,10 @@ QVector<QDBusObjectPath> WifiManager::list_connections(){
return connections;
}
bool WifiManager::activate_wifi_connection(const QString &ssid){
bool WifiManager::activate_wifi_connection(const QString &ssid) {
QString devicePath = get_adapter();
for(QDBusObjectPath path : list_connections()){
for(QDBusObjectPath path : list_connections()) {
QDBusInterface nm2(nm_service, path.path(), nm_settings_conn_iface, bus);
nm2.setTimeout(dbus_timeout);
@ -438,10 +438,10 @@ bool WifiManager::activate_wifi_connection(const QString &ssid){
return false;
}
//Functions for tethering
bool WifiManager::activate_tethering_connection(){
bool WifiManager::activate_tethering_connection() {
QString devicePath = get_adapter();
for(QDBusObjectPath path : list_connections()){
for(QDBusObjectPath path : list_connections()) {
QDBusInterface nm2(nm_service, path.path(), nm_settings_conn_iface, bus);
nm2.setTimeout(dbus_timeout);
@ -466,7 +466,7 @@ bool WifiManager::activate_tethering_connection(){
}
return false;
}
void WifiManager::addTetheringConnection(){
void WifiManager::addTetheringConnection() {
Connection connection;
connection["connection"]["id"] = "Hotspot";
connection["connection"]["uuid"] = QUuid::createUuid().toString().remove('{').remove('}');
@ -498,7 +498,7 @@ void WifiManager::addTetheringConnection(){
}
void WifiManager::enableTethering() {
if(activate_tethering_connection()){
if(activate_tethering_connection()) {
return;
}
addTetheringConnection();

View File

@ -48,7 +48,7 @@ void OnroadWindow::offroadTransition(bool offroad) {
#ifdef ENABLE_MAPS
if (!offroad) {
QString token = QString::fromStdString(Params().get("MapboxToken"));
if (map == nullptr && !token.isEmpty()){
if (map == nullptr && !token.isEmpty()) {
QMapboxGLSettings settings;
if (!Hardware::PC()) {
settings.setCacheDatabasePath("/data/mbgl-cache.db");
@ -227,7 +227,7 @@ void NvgWindow::initializeGL() {
void NvgWindow::update(const UIState &s) {
// Connecting to visionIPC requires opengl to be current
if (s.vipc_client->connected){
if (s.vipc_client->connected) {
makeCurrent();
}
repaint();

View File

@ -4,7 +4,7 @@ RequestRepeater::RequestRepeater(QObject *parent, const QString &requestURL, con
int period) : HttpRequest(parent, requestURL, cacheKey) {
timer = new QTimer(this);
timer->setTimerType(Qt::VeryCoarseTimer);
QObject::connect(timer, &QTimer::timeout, [=](){
QObject::connect(timer, &QTimer::timeout, [=]() {
if (!QUIState::ui_state.scene.started && QUIState::ui_state.awake && reply == NULL) {
sendRequest(requestURL);
}

View File

@ -28,7 +28,7 @@ int main(int argc, char *argv[]) {
layout->addWidget(scroll, 0, 0, Qt::AlignTop);
// Scroll to the bottom
QObject::connect(scroll->verticalScrollBar(), &QAbstractSlider::rangeChanged, [=](){
QObject::connect(scroll->verticalScrollBar(), &QAbstractSlider::rangeChanged, [=]() {
scroll->verticalScrollBar()->setValue(scroll->verticalScrollBar()->maximum());
});

View File

@ -59,8 +59,8 @@ AbstractControl::AbstractControl(const QString &title, const QString &desc, cons
setStyleSheet("background-color: transparent;");
}
void AbstractControl::hideEvent(QHideEvent *e){
if(description != nullptr){
void AbstractControl::hideEvent(QHideEvent *e) {
if(description != nullptr) {
description->hide();
}
}

View File

@ -74,7 +74,7 @@ int InputDialog::exec() {
return QDialog::exec();
}
void InputDialog::show(){
void InputDialog::show() {
setMainWindow(this);
}
@ -84,7 +84,7 @@ void InputDialog::handleInput(const QString &s) {
}
if (!QString::compare(s,"")) {
if (line->text().length() >= minLength){
if (line->text().length() >= minLength) {
done(QDialog::Accepted);
emitText(line->text());
} else {
@ -102,14 +102,14 @@ void InputDialog::handleInput(const QString &s) {
line->insert(s.left(1));
}
void InputDialog::setMessage(const QString &message, bool clearInputField){
void InputDialog::setMessage(const QString &message, bool clearInputField) {
label->setText(message);
if (clearInputField){
if (clearInputField) {
line->setText("");
}
}
void InputDialog::setMinLength(int length){
void InputDialog::setMinLength(int length) {
minLength = length;
}

View File

@ -2,7 +2,7 @@
#include <QScrollBar>
ScrollView::ScrollView(QWidget *w, QWidget *parent) : QScrollArea(parent){
ScrollView::ScrollView(QWidget *w, QWidget *parent) : QScrollArea(parent) {
setWidget(w);
setWidgetResizable(true);
setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff);
@ -42,6 +42,6 @@ ScrollView::ScrollView(QWidget *w, QWidget *parent) : QScrollArea(parent){
scroller->setScrollerProperties(sp);
}
void ScrollView::hideEvent(QHideEvent *e){
void ScrollView::hideEvent(QHideEvent *e) {
verticalScrollBar()->setValue(0);
}

View File

@ -27,11 +27,11 @@ PairingQRWidget::PairingQRWidget(QWidget* parent) : QWidget(parent) {
connect(timer, &QTimer::timeout, this, &PairingQRWidget::refresh);
}
void PairingQRWidget::showEvent(QShowEvent *event){
void PairingQRWidget::showEvent(QShowEvent *event) {
refresh();
}
void PairingQRWidget::refresh(){
void PairingQRWidget::refresh() {
Params params;
QString IMEI = QString::fromStdString(params.get("IMEI"));
QString serial = QString::fromStdString(params.get("HardwareSerial"));
@ -254,7 +254,7 @@ void SetupWidget::parseError(const QString &response) {
mainLayout->setCurrentIndex(0);
}
void SetupWidget::showQrCode(){
void SetupWidget::showQrCode() {
showQr = true;
mainLayout->setCurrentIndex(1);
}

View File

@ -35,12 +35,12 @@ void Toggle::paintEvent(QPaintEvent *e) {
}
void Toggle::mouseReleaseEvent(QMouseEvent *e) {
if(!enabled){
if(!enabled) {
return;
}
const int left = _radius;
const int right = width() - _radius;
if(_x_circle != left && _x_circle != right){
if(_x_circle != left && _x_circle != right) {
//Don't parse touch events, while the animation is running
return;
}
@ -65,13 +65,13 @@ void Toggle::enterEvent(QEvent *e) {
QAbstractButton::enterEvent(e);
}
bool Toggle::getEnabled(){
bool Toggle::getEnabled() {
return enabled;
}
void Toggle::setEnabled(bool value){
void Toggle::setEnabled(bool value) {
enabled = value;
if(value){
if(value) {
circleColor.setRgb(0xfafafa);
green.setRgb(0x33ab4c);
}else{

View File

@ -29,7 +29,7 @@ MainWindow::MainWindow(QWidget *parent) : QWidget(parent) {
main_layout->addWidget(onboardingWindow);
main_layout->setCurrentWidget(onboardingWindow);
QObject::connect(onboardingWindow, &OnboardingWindow::onboardingDone, [=](){
QObject::connect(onboardingWindow, &OnboardingWindow::onboardingDone, [=]() {
onboardingDone = true;
closeSettings();
});
@ -55,8 +55,8 @@ MainWindow::MainWindow(QWidget *parent) : QWidget(parent) {
)");
}
void MainWindow::offroadTransition(bool offroad){
if(!offroad){
void MainWindow::offroadTransition(bool offroad) {
if(!offroad) {
closeSettings();
}
}
@ -77,7 +77,7 @@ void MainWindow::reviewTrainingGuide() {
onboardingWindow->updateActiveScreen();
}
bool MainWindow::eventFilter(QObject *obj, QEvent *event){
bool MainWindow::eventFilter(QObject *obj, QEvent *event) {
// wake screen on tap
if (event->type() == QEvent::MouseButtonPress) {
device.setAwake(true, true);

View File

@ -121,7 +121,7 @@ static void update_model(UIState *s, const cereal::ModelDataV2::Reader &model) {
update_line_data(s, model_position, 0.5, 1.22, &scene.track_vertices, max_idx);
}
static void update_sockets(UIState *s){
static void update_sockets(UIState *s) {
s->sm->update(0);
}
@ -184,12 +184,12 @@ static void update_state(UIState *s) {
for (auto sensor : sm["sensorEvents"].getSensorEvents()) {
if (!scene.started && sensor.which() == cereal::SensorEventData::ACCELERATION) {
auto accel = sensor.getAcceleration().getV();
if (accel.totalSize().wordCount){ // TODO: sometimes empty lists are received. Figure out why
if (accel.totalSize().wordCount) { // TODO: sometimes empty lists are received. Figure out why
scene.accel_sensor = accel[2];
}
} else if (!scene.started && sensor.which() == cereal::SensorEventData::GYRO_UNCALIBRATED) {
auto gyro = sensor.getGyroUncalibrated().getV();
if (gyro.totalSize().wordCount){
if (gyro.totalSize().wordCount) {
scene.gyro_sensor = gyro[1];
}
}
@ -221,14 +221,14 @@ static void update_params(UIState *s) {
static void update_vision(UIState *s) {
if (!s->vipc_client->connected && s->scene.started) {
if (s->vipc_client->connect(false)){
if (s->vipc_client->connect(false)) {
ui_init_vision(s);
}
}
if (s->vipc_client->connected){
if (s->vipc_client->connected) {
VisionBuf * buf = s->vipc_client->recv();
if (buf != nullptr){
if (buf != nullptr) {
s->last_frame = buf;
} else if (!Hardware::PC()) {
LOGE("visionIPC receive timeout");
@ -263,7 +263,7 @@ static void update_status(UIState *s) {
ui_resize(s, s->fb_w, s->fb_h);
// Choose vision ipc client
if (s->wide_camera){
if (s->wide_camera) {
s->vipc_client = s->vipc_client_wide;
} else {
s->vipc_client = s->vipc_client_rear;