TestReading.cpp
Go to the documentation of this file.
1 
7 #include <gtest/gtest.h>
8 
9 #include <rokubimini/Reading.hpp>
10 
11 namespace rokubimini
12 {
13 class ReadingTest : public ::testing::Test
14 {
15 protected:
18  {
19  reading = new Reading();
20  }
21 
22  ~ReadingTest() override
23  {
24  delete reading;
25  // You can do clean-up work that doesn't throw exceptions here.
26  }
27 
28  // If the constructor and destructor are not enough for setting up
29  // and cleaning up each test, you can define the following methods:
30 
31  void SetUp() override
32  {
33  // Code here will be called immediately after the constructor (right
34  // before each test).
35  }
36 
37  void TearDown() override
38  {
39  // Code here will be called immediately after each test (right
40  // before the destructor).
41  }
42 };
43 
44 // TEST_F(ReadingTest, ImuWorksCorrectly)
45 // {
46 // ImuType imu;
47 // reading->setImu(imu);
48 // auto imu_expected = reading->getImu();
49 // EXPECT_EQ(imu, imu_expected);
50 // }
51 
52 // TEST_F(ReadingTest, WrenchWorksCorrectly)
53 // {
54 // WrenchType wrench;
55 // reading->setWrench(wrench);
56 // auto wrench_expected = reading->getWrench();
57 // EXPECT_EQ(wrench, wrench_expected);
58 // }
59 
60 // TEST_F(ReadingTest, ExternalImuWorksCorrectly)
61 // {
62 // ImuType imu;
63 // reading->setExternalImu(imu);
64 // auto imu_expected = reading->getExternalImu();
65 // EXPECT_EQ(imu, imu_expected);
66 // }
67 
68 TEST_F(ReadingTest, StatusWordWorksCorrectly)
69 {
70  Statusword word = Statusword();
71  reading->setStatusword(word);
72  auto word_expected = reading->getStatusword();
73  EXPECT_EQ(word.getData(), word_expected.getData());
74  EXPECT_EQ(word.getStamp(), word_expected.getStamp());
75  EXPECT_EQ(word.hasErrorAdcSaturated(), word_expected.hasErrorAdcSaturated());
76  EXPECT_EQ(word.hasErrorAccSaturated(), word_expected.hasErrorAccSaturated());
77  EXPECT_EQ(word.hasErrorGyroSaturated(), word_expected.hasErrorGyroSaturated());
78  EXPECT_EQ(word.hasErrorAdcOutOfSync(), word_expected.hasErrorAdcOutOfSync());
79  EXPECT_EQ(word.hasErrorSensingRangeExceeded(), word_expected.hasErrorSensingRangeExceeded());
80  EXPECT_EQ(word.hasWarningOvertemperature(), word_expected.hasWarningOvertemperature());
81  EXPECT_EQ(word.hasFatalSupplyVoltage(), word_expected.hasFatalSupplyVoltage());
82 }
83 
84 TEST_F(ReadingTest, ForceTorqueSaturatedWorksCorrectly)
85 {
87  auto force_torque_saturated = reading->isForceTorqueSaturated();
88  EXPECT_EQ(force_torque_saturated, true);
89 }
90 
91 TEST_F(ReadingTest, TemperatureWorksCorrectly)
92 {
93  auto temperature = sensor_msgs::Temperature();
94  temperature.temperature = 15.46329113;
95  reading->setTemperature(temperature);
96  auto temp = reading->getTemperature();
97  EXPECT_FLOAT_EQ(temp.temperature, 15.46329113);
98 }
99 
100 } // namespace rokubimini
bool hasErrorAccSaturated() const
Checks if the statusword has error ACC saturated.
Definition: Statusword.cpp:162
void SetUp() override
Definition: TestReading.cpp:31
bool hasErrorSensingRangeExceeded() const
Checks if the statusword has error sensing range exceeded.
Definition: Statusword.cpp:180
void TearDown() override
Definition: TestReading.cpp:37
Class representing the readings received from the rokubi mini devices.
Definition: Reading.hpp:35
Class representing the different states the communication or the sensors can be in.
Definition: Statusword.hpp:20
TEST_F(ReadingTest, StatusWordWorksCorrectly)
Definition: TestReading.cpp:68
uint32_t getData() const
Gets the data variable.
Definition: Statusword.cpp:63
bool isForceTorqueSaturated() const
Gets the isForceTorqueSaturated flag.
Definition: Reading.hpp:155
bool hasErrorGyroSaturated() const
Checks if the statusword has error gyro saturated.
Definition: Statusword.cpp:168
bool hasErrorAdcOutOfSync() const
Checks if the statusword has error ADC out-of-sync.
Definition: Statusword.cpp:174
void setStatusword(const Statusword &statusword)
Sets the statusword variable.
Definition: Reading.hpp:143
bool hasFatalSupplyVoltage() const
Checks if the statusword has fatal supply voltage.
Definition: Statusword.cpp:192
TimePoint getStamp() const
Gets the stamp variable.
Definition: Statusword.cpp:50
void setForceTorqueSaturated(const bool isForceTorqueSaturated)
Sets the isForceTorqueSaturated variable.
Definition: Reading.hpp:167
void setTemperature(const TempType &temperature)
Sets the temperature variable.
Definition: Reading.hpp:203
bool hasWarningOvertemperature() const
Checks if the statusword has warning over temperature.
Definition: Statusword.cpp:186
const Statusword & getStatusword() const
Gets the statusword variable.
Definition: Reading.hpp:131
bool hasErrorAdcSaturated() const
Checks if the statusword has error ADC saturated.
Definition: Statusword.cpp:156
const TempType & getTemperature() const
Gets the temperature flag.
Definition: Reading.hpp:179
Tests Configuration.


rokubimini
Author(s):
autogenerated on Wed Mar 3 2021 03:09:12