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 hasErrorAccSaturated() const
Checks if the statusword has error ACC saturated.
bool hasErrorSensingRangeExceeded() const
Checks if the statusword has error sensing range exceeded.
Class representing the readings received from the rokubi mini devices.
Class representing the different states the communication or the sensors can be in.
TEST_F(ReadingTest, StatusWordWorksCorrectly)
uint32_t getData() const
Gets the data variable.
bool isForceTorqueSaturated() const
Gets the isForceTorqueSaturated flag.
bool hasErrorGyroSaturated() const
Checks if the statusword has error gyro saturated.
bool hasErrorAdcOutOfSync() const
Checks if the statusword has error ADC out-of-sync.
void setStatusword(const Statusword &statusword)
Sets the statusword variable.
bool hasFatalSupplyVoltage() const
Checks if the statusword has fatal supply voltage.
TimePoint getStamp() const
Gets the stamp variable.
void setForceTorqueSaturated(const bool isForceTorqueSaturated)
Sets the isForceTorqueSaturated variable.
void setTemperature(const TempType &temperature)
Sets the temperature variable.
bool hasWarningOvertemperature() const
Checks if the statusword has warning over temperature.
const Statusword & getStatusword() const
Gets the statusword variable.
bool hasErrorAdcSaturated() const
Checks if the statusword has error ADC saturated.
const TempType & getTemperature() const
Gets the temperature flag.