7 #include <gtest/gtest.h> 73 EXPECT_EQ(word.
getData(), word_expected.getData());
74 EXPECT_EQ(word.
getStamp(), word_expected.getStamp());
88 EXPECT_EQ(force_torque_saturated,
true);
93 auto temperature = sensor_msgs::Temperature();
94 temperature.temperature = 15.46329113;
97 EXPECT_FLOAT_EQ(temp.temperature, 15.46329113);
bool hasErrorSensingRangeExceeded() const
Checks if the statusword has error sensing range exceeded.
bool hasErrorGyroSaturated() const
Checks if the statusword has error gyro saturated.
bool hasErrorAccSaturated() const
Checks if the statusword has error ACC saturated.
uint32_t getData() const
Gets the data variable.
const TempType & getTemperature() const
Gets the temperature flag.
Class representing the readings received from the rokubi mini devices.
const Statusword & getStatusword() const
Gets the statusword variable.
Class representing the different states the communication or the sensors can be in.
TEST_F(ReadingTest, StatusWordWorksCorrectly)
TimePoint getStamp() const
Gets the stamp variable.
void setStatusword(const Statusword &statusword)
Sets the statusword variable.
void setForceTorqueSaturated(const bool isForceTorqueSaturated)
Sets the isForceTorqueSaturated variable.
bool hasFatalSupplyVoltage() const
Checks if the statusword has fatal supply voltage.
bool hasErrorAdcSaturated() const
Checks if the statusword has error ADC saturated.
void setTemperature(const TempType &temperature)
Sets the temperature variable.
bool isForceTorqueSaturated() const
Gets the isForceTorqueSaturated flag.
bool hasErrorAdcOutOfSync() const
Checks if the statusword has error ADC out-of-sync.
bool hasWarningOvertemperature() const
Checks if the statusword has warning over temperature.