Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions boards/varmint_h7/common/Varmint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -208,9 +208,9 @@ bool Varmint::diff_pressure_read(rosflight_firmware::PressureStruct * diff_press

///////////////////////////////////////////////////////////////////////////////////////////////
// Sonar
bool Varmint::sonar_read(rosflight_firmware::RangeStruct * sonar)
bool Varmint::range_read(rosflight_firmware::RangeStruct * range)
{
(void) sonar; // unused
(void) range; // unused
return false;
}

Expand Down
2 changes: 1 addition & 1 deletion boards/varmint_h7/common/Varmint.h
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@ class Varmint : public rosflight_firmware::Board

bool diff_pressure_read(rosflight_firmware::PressureStruct * diff_pressure) override;

bool sonar_read(rosflight_firmware::RangeStruct * sonar) override;
bool range_read(rosflight_firmware::RangeStruct * range) override;

// Battery
bool battery_read(rosflight_firmware::BatteryStruct * bat) override;
Expand Down
4 changes: 2 additions & 2 deletions comms/mavlink/mavlink.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
/*
/*
* Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab
*
* All rights reserved.
Expand Down Expand Up @@ -250,7 +250,7 @@ void Mavlink::send_rc_raw(uint8_t system_id, uint32_t timestamp_ms, const uint16
send_message(msg);
}

void Mavlink::send_sonar(uint8_t system_id,
void Mavlink::send_range(uint8_t system_id,
/* TODO enum type*/ uint8_t type, float range, float max_range,
float min_range)
{
Expand Down
2 changes: 1 addition & 1 deletion comms/mavlink/mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ class Mavlink : public CommLinkInterface
void send_param_value_float(uint8_t system_id, uint16_t index, const char * const name,
float value, uint16_t param_count) override;
void send_rc_raw(uint8_t system_id, uint32_t timestamp_ms, const uint16_t channels[8]) override;
void send_sonar(uint8_t system_id,
void send_range(uint8_t system_id,
/* TODO enum type*/ uint8_t type, float range, float max_range,
float min_range) override;
void send_status(uint8_t system_id, bool armed, bool failsafe, uint16_t rc_override, bool offboard,
Expand Down
2 changes: 1 addition & 1 deletion include/comm_link.h
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ class CommLinkInterface
float value, uint16_t param_count) = 0;
virtual void send_rc_raw(uint8_t system_id, uint32_t timestamp_ms,
const uint16_t channels[8]) = 0;
virtual void send_sonar(uint8_t system_id,
virtual void send_range(uint8_t system_id,
/* TODO enum type*/ uint8_t type, float range, float max_range,
float min_range) = 0;
virtual void send_status(uint8_t system_id, bool armed, bool failsafe, uint16_t rc_override,
Expand Down
2 changes: 1 addition & 1 deletion include/comm_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,7 @@ class CommManager : public CommLinkInterface::ListenerInterface, public ParamLis
void send_output_raw(void);
void send_diff_pressure(void);
void send_baro(void);
void send_sonar(void);
void send_range(void);
void send_mag(void);
void send_battery_status(void);
void send_gnss(void);
Expand Down
4 changes: 2 additions & 2 deletions include/interface/board.h
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,7 @@ typedef struct
bool baro;
bool mag;
bool diff_pressure;
bool sonar;
bool range;
bool battery;
} got_flags;

Expand Down Expand Up @@ -206,7 +206,7 @@ class Board
virtual bool diff_pressure_read(PressureStruct * diff_pressure) = 0;

// Sonar
virtual bool sonar_read(RangeStruct * sonar) = 0;
virtual bool range_read(RangeStruct * range) = 0;

// GPS
virtual bool gnss_read(rosflight_firmware::GnssStruct * gnss) = 0;
Expand Down
4 changes: 2 additions & 2 deletions include/sensors.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ class Sensors : public ParamListenerInterface
public:
PressureStruct * get_diff_pressure(void) { return &diff_pressure_; }
PressureStruct * get_baro(void) { return &baro_; }
RangeStruct * get_sonar(void) { return &sonar_; }
RangeStruct * get_range(void) { return &range_; }
ImuStruct * get_imu(void) { return &imu_; }
BatteryStruct * get_battery(void) { return &battery_; }
MagStruct * get_mag(void) { return &mag_; }
Expand All @@ -79,7 +79,7 @@ class Sensors : public ParamListenerInterface
// Data
PressureStruct diff_pressure_ = {};
PressureStruct baro_ = {};
RangeStruct sonar_ = {};
RangeStruct range_ = {};
ImuStruct imu_ = {};
BatteryStruct battery_ = {};
MagStruct mag_ = {};
Expand Down
8 changes: 4 additions & 4 deletions src/comm_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -419,11 +419,11 @@ void CommManager::send_baro(void)
RF_.sensors_.get_baro()->temperature);
}

void CommManager::send_sonar(void)
void CommManager::send_range(void)
{
comm_link_.send_sonar(sysid_,
comm_link_.send_range(sysid_,
0, // TODO set sensor type (sonar/lidar), use enum
RF_.sensors_.get_sonar()->range, 8.0, 0.25);
RF_.sensors_.get_range()->range, 8.0, 0.25);
}

void CommManager::send_mag(void)
Expand Down Expand Up @@ -496,7 +496,7 @@ void CommManager::stream(got_flags got)
// Magnetometer
if (got.mag) { send_mag(); }
// Height above ground sensor
if (got.sonar) { send_sonar(); }
if (got.range) { send_range(); }
// Battery V & I
if (got.battery) { send_battery_status(); }
// GPS data (GNSS Packed)
Expand Down
2 changes: 1 addition & 1 deletion src/sensors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -200,7 +200,7 @@ got_flags Sensors::run()
}

// SONAR:
got.sonar = rf_.board_.sonar_read(&sonar_);
got.range = rf_.board_.range_read(&range_);

// BATTERY_MONITOR:
if ((got.battery = rf_.board_.battery_read(&battery_))) {
Expand Down
6 changes: 3 additions & 3 deletions test/test_board.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,9 +122,9 @@
return false;
}

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

Expand Down Expand Up @@ -163,4 +163,4 @@
} // namespace rosflight_firmware

#pragma GCC diagnostic pop


4 changes: 2 additions & 2 deletions test/test_board.h
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@

bool diff_pressure_read(rosflight_firmware::PressureStruct * diff_pressure) override;

bool sonar_read(rosflight_firmware::RangeStruct * sonar) override;
bool range_read(rosflight_firmware::RangeStruct * range) override;

// Battery
bool battery_read(rosflight_firmware::BatteryStruct * bat) override;
Expand Down Expand Up @@ -130,4 +130,4 @@
} // namespace rosflight_firmware

#endif // ROSLFIGHT_FIRMWARE_TEST_BOARD_H