diff --git a/include/board.h b/include/board.h index 91d28f58..61133899 100644 --- a/include/board.h +++ b/include/board.h @@ -93,17 +93,17 @@ class Board // Sonar virtual bool sonar_present() = 0; virtual uint8_t sonar_has_new_data() = 0; - virtual bool sonar_read(float *range) =0; + virtual bool sonar_read(float *range) = 0; // GPS virtual bool gnss_present() = 0; virtual uint8_t gnss_has_new_data() = 0; - virtual bool gnss_read( GNSSData *gnss, GNSSFull *gnss_full) = 0; + virtual bool gnss_read(GNSSData *gnss, GNSSFull *gnss_full) = 0; // Battery - virtual bool battery_present() = 0; - virtual uint8_t battery_has_new_data() = 0; - virtual bool battery_read(float *voltage, float* current) = 0; + virtual bool battery_present() = 0; + virtual uint8_t battery_has_new_data() = 0; + virtual bool battery_read(float *voltage, float *current) = 0; virtual void battery_voltage_set_multiplier(double multiplier) = 0; virtual void battery_current_set_multiplier(double multiplier) = 0; diff --git a/include/sensors.h b/include/sensors.h index fcedca51..46914dd4 100644 --- a/include/sensors.h +++ b/include/sensors.h @@ -162,7 +162,7 @@ class Sensors : public ParamListenerInterface GNSSFull gnss_full; float gps_CNO = 0; // What is this? bool gnss_present = false; - + turbomath::Vector mag = {0, 0, 0}; bool baro_present = false; diff --git a/src/comm_manager.cpp b/src/comm_manager.cpp index 172373c5..f28b5a5b 100644 --- a/src/comm_manager.cpp +++ b/src/comm_manager.cpp @@ -522,40 +522,57 @@ void CommManager::stream(got_flags got) // Send out data - if(got.imu) // Nominally 400Hz + if (got.imu) // Nominally 400Hz { send_imu(); send_attitude(); - static uint64_t ro_count=0; - if(!((ro_count++)%8)) send_output_raw(); // Raw output at 400Hz/8 = 50Hz - } - - if(got.diff_pressure) send_diff_pressure(); // Pitot sensor - if(got.baro) send_baro(); // Baro altimeter - if(got.mag) send_mag(); // Manetometer - if(got.sonar) send_sonar(); // Height above ground sensor (not enabled) - if(got.battery) send_battery_status(); // Battery V & I - if(got.gnss) send_gnss(); // GPS data (GNSS Packed) - if(got.gnss_full) send_gnss_full(); // GPS full data (not needed) - if(got.rc) // report at half the S.Bus rate. + static uint64_t ro_count = 0; + if (!((ro_count++) % 8)) + send_output_raw(); // Raw output at 400Hz/8 = 50Hz + } + + // Pitot sensor + if (got.diff_pressure) + send_diff_pressure(); + // Baro altitude + if (got.baro) + send_baro(); + // Magnetometer + if (got.mag) + send_mag(); + // Height above ground sensor (not enabled) + if (got.sonar) + send_sonar(); + // Battery V & I + if (got.battery) + send_battery_status(); + // GPS data (GNSS Packed) + if (got.gnss) + send_gnss(); + // GPS full data (not needed) + if (got.gnss_full) + send_gnss_full(); + if (got.rc) // report at half the S.Bus rate. { - static uint64_t rc_count=0; - if(!((rc_count++)%2)) send_rc_raw(); // RC (S.Bus) inputs, scaled 1000-2000 + static uint64_t rc_count = 0; + // RC (S.Bus) inputs, scaled 1000-2000 + if (!((rc_count++) % 2)) + send_rc_raw(); } { - static uint64_t next_heartbeat = 0, next_status =0; - - if((time_us)/1000000 >= next_heartbeat ) // 1 Hz - { - send_heartbeat(); - next_heartbeat = time_us/1000000+1; - } - if((time_us)/100000 >= next_status ) // 10 Hz - { - send_status(); - next_status = time_us/100000+1; - } + static uint64_t next_heartbeat = 0, next_status = 0; + + if ((time_us) / 1000000 >= next_heartbeat) // 1 Hz + { + send_heartbeat(); + next_heartbeat = time_us / 1000000 + 1; + } + if ((time_us) / 100000 >= next_status) // 10 Hz + { + send_status(); + next_status = time_us / 100000 + 1; + } } send_low_priority(); // parameter values and logging messages @@ -581,9 +598,7 @@ void CommManager::send_next_param(void) } CommManager::Stream::Stream(uint32_t period_us, std::function send_function) : - period_us_(period_us), - next_time_us_(0), - send_function_(send_function) + period_us_(period_us), next_time_us_(0), send_function_(send_function) { } diff --git a/src/param.cpp b/src/param.cpp index 2287e6d3..3dfa92ec 100644 --- a/src/param.cpp +++ b/src/param.cpp @@ -49,10 +49,10 @@ #endif // Uncomment to view contents of GIT_VERSION_HASH and GIT_VERSION STRING -//#define STRINGIFY(s) XSTRINGIFY(s) -//#define XSTRINGIFY(s) #s -//#pragma message( "GIT_VERSION_HASH: " STRINGIFY(GIT_VERSION_HASH)) -//#pragma message( "GIT_VERSION_STRING: " GIT_VERSION_STRING) +// #define STRINGIFY(s) XSTRINGIFY(s) +// #define XSTRINGIFY(s) #s +// #pragma message( "GIT_VERSION_HASH: " STRINGIFY(GIT_VERSION_HASH)) +// #pragma message( "GIT_VERSION_STRING: " GIT_VERSION_STRING) namespace rosflight_firmware { diff --git a/src/rosflight.cpp b/src/rosflight.cpp index 8f95b9a9..db254d64 100644 --- a/src/rosflight.cpp +++ b/src/rosflight.cpp @@ -108,9 +108,9 @@ void ROSflight::run() /*********************/ uint64_t start = board_.clock_micros(); - got_flags got = sensors_.run(); // IMU, GNSS, Baro, Mag, Pitot, SONAR, Battery + got_flags got = sensors_.run(); // IMU, GNSS, Baro, Mag, Pitot, SONAR, Battery - if(got.imu) + if (got.imu) { estimator_.run(); controller_.run(); @@ -131,7 +131,8 @@ void ROSflight::run() state_manager_.run(); // get RC, synchronous with rc data acquisition - if(got.rc) rc_.run(); + if (got.rc) + rc_.run(); // update commands (internal logic tells whether or not we should do anything or not) command_manager_.run(); diff --git a/src/sensors.cpp b/src/sensors.cpp index 8936c17a..a4c88fd5 100644 --- a/src/sensors.cpp +++ b/src/sensors.cpp @@ -128,10 +128,10 @@ void Sensors::param_change_callback(uint16_t param_id) got_flags Sensors::run() { - memset(&got,0,sizeof(got)); + memset(&got, 0, sizeof(got)); // IMU: - if ((got.imu = rf_.board_.imu_has_new_data())>0) + if ((got.imu = rf_.board_.imu_has_new_data()) > 0) { rf_.state_manager_.clear_error(StateManager::ERROR_IMU_NOT_RESPONDING); last_imu_update_ms_ = rf_.board_.clock_millis(); @@ -165,16 +165,15 @@ got_flags Sensors::run() accel_int_ += dt * data_.accel; gyro_int_ += dt * data_.gyro; prev_imu_read_time_us_ = data_.imu_time; - } // GNSS: if (rf_.board_.gnss_present()) { data_.gnss_present = true; - if((got.gnss = rf_.board_.gnss_has_new_data())>0) + if ((got.gnss = rf_.board_.gnss_has_new_data()) > 0) { - rf_.board_.gnss_read(&this->data_.gnss_data, &this->data_.gnss_full); + rf_.board_.gnss_read(&this->data_.gnss_data, &this->data_.gnss_full); } got.gnss_full = got.gnss; // bot come with the pvt GPS data } @@ -183,8 +182,8 @@ got_flags Sensors::run() if (rf_.board_.baro_present()) { data_.baro_present = true; - if((got.baro = rf_.board_.baro_has_new_data())>0) - { + if ((got.baro = rf_.board_.baro_has_new_data()) > 0) + { float raw_pressure; float raw_temp; rf_.board_.baro_read(&raw_pressure, &raw_temp); @@ -202,7 +201,7 @@ got_flags Sensors::run() { data_.mag_present = true; float mag[3]; - if((got.mag=rf_.board_.mag_has_new_data())>0) + if ((got.mag = rf_.board_.mag_has_new_data()) > 0) { rf_.board_.mag_read(mag); data_.mag.x = mag[0]; @@ -216,7 +215,7 @@ got_flags Sensors::run() if (rf_.board_.diff_pressure_present()) { data_.diff_pressure_present = true; - if((got.diff_pressure = rf_.board_.diff_pressure_has_new_data())>0) + if ((got.diff_pressure = rf_.board_.diff_pressure_has_new_data()) > 0) { float raw_pressure; float raw_temp; @@ -234,33 +233,33 @@ got_flags Sensors::run() if (rf_.board_.sonar_present()) { data_.sonar_present = true; - if((got.sonar = rf_.board_.sonar_has_new_data())>0) + if ((got.sonar = rf_.board_.sonar_has_new_data()) > 0) { float raw_distance; - rf_.board_.sonar_read( &raw_distance); + rf_.board_.sonar_read(&raw_distance); data_.sonar_range_valid = sonar_outlier_filt_.update(raw_distance, &data_.sonar_range); } } // BATTERY_MONITOR: - if((got.battery = rf_.board_.battery_has_new_data())>0) + if ((got.battery = rf_.board_.battery_has_new_data()) > 0) { last_battery_monitor_update_ms_ = rf_.board_.clock_millis(); update_battery_monitor(); } // RC - if((got.rc = rf_.board_.rc_has_new_data())>0) + if ((got.rc = rf_.board_.rc_has_new_data()) > 0) { rf_.board_.rc_read(0); } - return got; + return got; } -void Sensors::update_other_sensors(){} +void Sensors::update_other_sensors() {} -void Sensors::look_for_disabled_sensors(){} +void Sensors::look_for_disabled_sensors() {} bool Sensors::start_imu_calibration(void) { @@ -312,7 +311,7 @@ bool Sensors::gyro_calibration_complete(void) bool Sensors::update_imu(void) { bool new_data; - if ((new_data = rf_.board_.imu_has_new_data())>0) + if ((new_data = rf_.board_.imu_has_new_data()) > 0) { rf_.state_manager_.clear_error(StateManager::ERROR_IMU_NOT_RESPONDING); last_imu_update_ms_ = rf_.board_.clock_millis(); @@ -345,9 +344,8 @@ bool Sensors::update_imu(void) accel_int_ += dt * data_.accel; gyro_int_ += dt * data_.gyro; prev_imu_read_time_us_ = data_.imu_time; - - } - return new_data; + } + return new_data; } void Sensors::get_filtered_IMU(turbomath::Vector &accel, turbomath::Vector &gyro, uint64_t &stamp_us) @@ -365,8 +363,8 @@ void Sensors::update_battery_monitor() { if (rf_.board_.battery_present()) { - float battery_voltage,battery_current; - rf_.board_.battery_read(&battery_voltage,&battery_current); + float battery_voltage, battery_current; + rf_.board_.battery_read(&battery_voltage, &battery_current); data_.battery_monitor_present = true; data_.battery_voltage = battery_voltage; data_.battery_current = battery_current;