20 #include <gtest/gtest.h> 22 #include <prbt_hardware_support/GetSpeedOverride.h> 23 #include <dynamic_reconfigure/Reconfigure.h> 24 #include <prbt_hardware_support/FakeSpeedOverrideConfig.h> 34 void SetUp()
override;
40 prbt_hardware_support::GetSpeedOverride
srv;
42 FakeSpeedOverrideConfig
conf;
48 client = n.
serviceClient<prbt_hardware_support::GetSpeedOverride>(
"/prbt/get_speed_override");
54 dynamic_reconfigure::Reconfigure rec;
55 dynamic_reconfigure::DoubleParameter speed_override_param;
56 speed_override_param.name =
"speed_override";
57 speed_override_param.value = speed_override;
59 rec.request.config.doubles.push_back(speed_override_param);
81 EXPECT_EQ(
srv.response.speed_override,
conf.__getDefault__().speed_override);
83 const auto test_value = 0.5;
86 EXPECT_EQ(
srv.response.speed_override, test_value);
94 EXPECT_EQ(
srv.response.speed_override,
conf.__getMin__().speed_override);
102 EXPECT_EQ(
srv.response.speed_override,
conf.__getMax__().speed_override);
107 int main(
int argc,
char** argv)
109 ros::init(argc, argv,
"unittest_fake_speed_override");
112 testing::InitGoogleTest(&argc, argv);
113 return RUN_ALL_TESTS();
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
int main(int argc, char **argv)
static constexpr double EXPECTED_DEFAULT_SPEED_OVERRIDE
bool setSpeedOverrideParameter(double speed_override)
prbt_hardware_support::GetSpeedOverride srv
TEST_F(BrakeTestRequiredIntegrationTest, testBrakeTestAnnouncement)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
ros::ServiceClient dynamic_parameter_client
ros::ServiceClient client
FakeSpeedOverrideConfig conf