Skip to content

Commit

Permalink
Updated test built
Browse files Browse the repository at this point in the history
  • Loading branch information
avtoku committed Nov 14, 2024
1 parent b1a22f6 commit 42c2c7e
Show file tree
Hide file tree
Showing 4 changed files with 42 additions and 80 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
# cmake --build . -j
# to run test:
# cmake . -DBOARD_TO_BUILD=test -DCMAKE_BUILD_TYPE=Release
# cmake
# make

cmake_minimum_required(VERSION 3.8)
project(rosflight_firmware C CXX ASM)
Expand Down
2 changes: 1 addition & 1 deletion boards/varmint_h7
67 changes: 22 additions & 45 deletions test/test_board.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,8 @@ void testBoard::set_imu(float * acc, float * gyro, uint64_t time_us)
new_imu_ = true;
}



// setup
void testBoard::init_board() { backup_memory_clear(); }
void testBoard::board_reset(bool bootloader) {}
Expand All @@ -79,28 +81,18 @@ uint16_t testBoard::sensors_init_message_count() { return 0; }
uint16_t testBoard::sensors_init_message(char * message, uint16_t size, uint16_t i) { return 0; }
bool testBoard::sensors_init_message_good(uint16_t i) { return false; }

bool testBoard::imu_present() { return false; }

bool testBoard::imu_has_new_data()
{
if (new_imu_) {
new_imu_ = false;
return true;
}
return false;
}

bool testBoard::imu_read(float accel[3], float * temperature, float gyro[3], uint64_t * time)
bool testBoard::imu_read(rosflight_firmware::ImuStruct * imu)
{
for (int i = 0; i < 3; i++) {
accel[i] = acc_[i];
gyro[i] = gyro_[i];
imu->accel[i] = acc_[i];
imu->gyro[i] = gyro_[i];
}
*temperature = 25.0;
*time = time_us_;
imu->temperature = 25.0;
imu->timestamp = time_us_;
return true;
}

void testBoard::backup_memory_init() {}
bool testBoard::backup_memory_read(void * dest, size_t len)
{
bool success = true;
Expand All @@ -117,51 +109,36 @@ void testBoard::backup_memory_write(const void * src, size_t len)
if (len > BACKUP_MEMORY_SIZE) { len = BACKUP_MEMORY_SIZE; }
memcpy(backup_memory_, src, len);
}

void testBoard::backup_memory_clear(size_t len) { memset(backup_memory_, 0, len); }
void testBoard::backup_memory_clear() { backup_memory_clear(BACKUP_MEMORY_SIZE); }

void testBoard::imu_not_responding_error() {}

bool testBoard::mag_present() { return false; }
bool testBoard::mag_has_new_data() { return false; }
bool testBoard::mag_read(float mag[3]) { return false; }
bool testBoard::mag_read(rosflight_firmware::MagStruct * mag) { (void)mag; return false; }

bool testBoard::baro_present() { return false; }
bool testBoard::baro_has_new_data() { return false; }
bool testBoard::baro_read(float * pressure, float * temperature) { return false; }
bool testBoard::baro_read(rosflight_firmware::PressureStruct * baro) { (void)baro; return false; }

bool testBoard::diff_pressure_present() { return false; }
bool testBoard::diff_pressure_has_new_data() { return false; }
bool testBoard::diff_pressure_read(float * diff_pressure, float * temperature) { return false; }
bool testBoard::diff_pressure_read(rosflight_firmware::PressureStruct * diff_pressure) { (void)diff_pressure; return false; }

bool testBoard::sonar_present() { return false; }
bool testBoard::sonar_has_new_data() { return false; }
bool testBoard::sonar_read(float * range) { return false; }
bool testBoard::sonar_read(rosflight_firmware::RangeStruct * sonar) { (void) sonar; return false; }

bool testBoard::gnss_present() { return false; }
bool testBoard::gnss_has_new_data() { return false; }
bool testBoard::gnss_read(GNSSData * gnss, GNSSFull * gnss_full) { return false; }
bool testBoard::gnss_read(rosflight_firmware::GnssStruct * gnss) { return false; }

bool testBoard::battery_present() { return false; }
bool testBoard::battery_has_new_data() { return false; }
bool testBoard::battery_read(float * voltage, float * current) { return false; }
bool testBoard::battery_read(rosflight_firmware::BatteryStruct * batt) { (void)batt; return false; }
void testBoard::battery_voltage_set_multiplier(double multiplier) {}
void testBoard::battery_current_set_multiplier(double multiplier) {}

// PWM
// TODO make these deal in normalized (-1 to 1 or 0 to 1) values (not pwm-specific)
void testBoard::rc_init(rc_type_t rc_type) {}
void testBoard::rc_init(rc_type_t rc_type) {(void)rc_type;}
bool testBoard::rc_lost() { return rc_lost_; }
bool testBoard::rc_has_new_data() { return new_rc_; }
float testBoard::rc_read(uint8_t channel)

bool testBoard::rc_read(rosflight_firmware::RcStruct * rc_struct)
{
new_rc_ = false;
return static_cast<float>(rc_values[channel] - 1000) / 1000.0;
// ???? what goes here ???
return true;
}
void testBoard::pwm_write(uint8_t channel, float value) {}
void testBoard::pwm_write_multi(float * value, uint32_t channels) {}
void testBoard::pwm_init(uint32_t refresh_rate, uint16_t idle_pwm) {}
void testBoard::pwm_init_multi(const float * rate, uint32_t channels) {}
void testBoard::pwm_write(float * value, uint32_t channels) {}
void testBoard::pwm_init(const float * rate, uint32_t channels) {}
void testBoard::pwm_disable() {}

// non-volatile memory
Expand Down
51 changes: 18 additions & 33 deletions test/test_board.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,8 @@ class testBoard : public Board

public:
// setup
void init_board() override;

void init_board(void) override;
void board_reset(bool bootloader) override;

// clock
Expand All @@ -74,49 +75,33 @@ class testBoard : public Board
uint16_t sensors_init_message(char * message, uint16_t size, uint16_t i) override;
bool sensors_init_message_good(uint16_t i) override;

bool imu_present() override;
bool imu_has_new_data() override;
bool imu_read(float accel[3], float * temperature, float gyro[3], uint64_t * time) override;
void imu_not_responding_error() override;

bool mag_present() override;
bool mag_has_new_data() override;
bool mag_read(float mag[3]) override;
bool imu_read(rosflight_firmware::ImuStruct * imu) override;

bool baro_present() override;
bool baro_has_new_data() override;
bool baro_read(float * pressure, float * temperature) override;
bool mag_read(rosflight_firmware::MagStruct * mag) override;

bool diff_pressure_present() override;
bool diff_pressure_has_new_data() override;
bool diff_pressure_read(float * diff_pressure, float * temperature) override;
bool baro_read(rosflight_firmware::PressureStruct * baro) override;

bool sonar_present() override;
bool sonar_has_new_data() override;
bool sonar_read(float * range) override;
bool diff_pressure_read(rosflight_firmware::PressureStruct * diff_pressure) override;

bool gnss_present() override;
bool gnss_has_new_data() override;
bool gnss_read(GNSSData * gnss, GNSSFull * gnss_full) override;
bool sonar_read(rosflight_firmware::RangeStruct * sonar) override;

bool battery_present() override;
bool battery_has_new_data() override;
bool battery_read(float * voltage, float * current) override;
// Battery
bool battery_read(rosflight_firmware::BatteryStruct * bat) override;
void battery_voltage_set_multiplier(double multiplier) override;
void battery_current_set_multiplier(double multiplier) override;

// GNSS
bool gnss_read(rosflight_firmware::GnssStruct * gnss) override;

// RC
void rc_init(rc_type_t rc_type) override;
bool rc_lost() override;
bool rc_has_new_data() override;
float rc_read(uint8_t channel) override;
bool rc_read(rosflight_firmware::RcStruct * rc) override;

// PWM
void pwm_init(uint32_t refresh_rate, uint16_t idle_pwm) override;
void pwm_init_multi(const float * rate, uint32_t channels) override;
void pwm_init(const float * rate, uint32_t channels) override;
void pwm_disable() override;
void pwm_write(uint8_t channel, float value) override;
void pwm_write_multi(float * value, uint32_t channels) override;
void pwm_write(float * value, uint32_t channels) override;

// non-volatile memory
void memory_init() override;
Expand All @@ -132,12 +117,12 @@ class testBoard : public Board
void led1_off() override;
void led1_toggle() override;

// Backup memory
void backup_memory_init() override {}
// Backup Data
void backup_memory_init() override;
bool backup_memory_read(void * dest, size_t len) override;
void backup_memory_write(const void * src, size_t len) override;
void backup_memory_clear(size_t len) override;
void backup_memory_clear(); // Not an override
void backup_memory_clear();

void set_imu(float * acc, float * gyro, uint64_t time_us);
void set_rc(uint16_t * values);
Expand Down

0 comments on commit 42c2c7e

Please sign in to comment.