18 #include <gtest/gtest.h> 19 #include <gmock/gmock.h> 40 TEST(ModbusApiSpecTest, testModbusApiSpecExceptionDtor)
45 TEST(ModbusApiSpecTest, ConstructionViaInitilizerListRead)
48 ASSERT_TRUE(api_spec.hasRegisterDefinition(
"test"));
49 EXPECT_EQ(123u, api_spec.getRegisterDefinition(
"test"));
51 EXPECT_EQ(123u, api_spec.getMinRegisterDefinition());
52 EXPECT_EQ(123u, api_spec.getMaxRegisterDefinition());
55 TEST(ModbusApiSpecTest, ConstructionViaInitilizerListReadNonExistent)
63 TEST(ModbusApiSpecTest, ConstructionViaInitilizerListOverwrite)
67 EXPECT_EQ(123u, api_spec.getMinRegisterDefinition());
68 EXPECT_EQ(234u, api_spec.getMaxRegisterDefinition());
71 ASSERT_TRUE(api_spec.hasRegisterDefinition(
"test"));
72 EXPECT_EQ(555u, api_spec.getRegisterDefinition(
"test"));
74 EXPECT_EQ(234u, api_spec.getMinRegisterDefinition());
75 EXPECT_EQ(555u, api_spec.getMaxRegisterDefinition());
78 TEST(ModbusApiSpecTest, NodeHandleConstructionSimpleRead)
84 EXPECT_CALL(nh,
getParam(
"read_api_spec/",_))
85 .WillOnce(DoAll(SetArgReferee<1>(rpc_value), Return(
true)));
89 ASSERT_TRUE(api_spec.hasRegisterDefinition(
"A"));
90 EXPECT_EQ(123u, api_spec.getRegisterDefinition(
"A"));
94 TEST(ModbusApiSpecTest, NodeHandleConstructionMissingApiSpec)
100 EXPECT_CALL(nh,
getParam(
"read_api_spec/",_))
102 .WillOnce(Return(
false));
107 .WillOnce(Return(
"testnamespace"));
112 int main(
int argc,
char **argv){
113 testing::InitGoogleTest(&argc, argv);
114 return RUN_ALL_TESTS();
Expection thrown by prbt_hardware_support::ModbusApiSpec.
ROSCPP_DECL const std::string & getNamespace()
void setRegisterDefinition(const std::string &key, unsigned short value)
int main(int argc, char **argv)
T getParam(const ros::NodeHandle &nh, const std::string ¶m_name)
TEST(IntegrationtestExecuteBrakeTest, testBrakeTestService)
Specifies the meaning of the holding registers.