18 #include <gtest/gtest.h> 22 #include <prbt_hardware_support/BrakeTest.h> 23 #include <prbt_hardware_support/WriteModbusRegister.h> 44 unsigned short register_perf,
45 unsigned short register_res,
47 float sleep_per_try_s,
48 unsigned short retries)
50 RegCont content_perf, content_res;
51 for(
int i = 0; i <= retries; i++){
52 ROS_INFO(
"Retry %d, waited for %.1fs so far", i, sleep_per_try_s * static_cast<float>(i));
56 content_perf[0] == expectation &&
57 content_res[0] == expectation)
85 TEST(IntegrationtestExecuteBrakeTest, testBrakeTestService)
95 ASSERT_TRUE(nh_private.
getParam(
"modbus_server_ip", ip));
96 ASSERT_TRUE(nh_private.
getParam(
"modbus_server_port", port));
99 unsigned int modbus_register_size {write_api_spec.getMaxRegisterDefinition() + 1U};
101 std::thread modbus_server_thread( &initalizeAndRun<prbt_hardware_support::PilzModbusServerMock>,
102 std::ref(modbus_server), ip.c_str(),
static_cast<unsigned int>(port) );
133 EXPECT_TRUE(brake_test_srv_client_.
call(srv));
151 modbus_server_thread.join();
156 int main(
int argc,
char *argv[])
158 ros::init(argc, argv,
"integrationtest_trigger_brake_test");
164 testing::InitGoogleTest(&argc, argv);
165 return RUN_ALL_TESTS();
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
static const std::string MODBUS_WRITE_SERVICE_NAME
static const std::string BRAKETEST_PERFORMED
static constexpr uint16_t MODBUS_BRAKE_TEST_PREPARE_VALUE
Offers a modbus server and read/write functionality via subscription/publication. ...
Mocks the ROS Api of the manipulator relevant for stopping and holding.
std::vector< uint16_t > RegCont
Convenience data type defining the data type for a collection of registers.
RegCont readHoldingRegister(const RegCont::size_type start_index, const RegCont::size_type num_reg_to_read)
Reads the specified number of registers, beginning at the specified start point from the holding regi...
static const std::string BRAKETEST_RESULT
static constexpr uint16_t MODBUS_BRAKE_TEST_EXPECTED_VALUE
void setHoldingRegister(std::initializer_list< std::pair< unsigned int, uint16_t > > reg_list)
bool brakeTestRegisterSetOnServer(PilzModbusServerMock &server, unsigned short register_perf, unsigned short register_res, uint16_t expectation, float sleep_per_try_s, unsigned short retries)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
void startAsync(bool move=false)
Start a new thread publishing joint states.
Asynchronously publishes predefined messages on the /joint_states topic with rate ~100Hz...
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
static const std::string CONTROLLER_HOLD_MODE_SERVICE_NAME
static const std::string EXECUTE_BRAKE_TEST_SERVICE_NAME
void terminate()
Terminate the Server. Reading or connecting to it will fail.
int main(int argc, char *argv[])
void advertiseHoldService(ros::NodeHandle nh, std::string hold_service_name)
void advertiseUnholdService(ros::NodeHandle nh, std::string unhold_service_name)
bool getParam(const std::string &key, std::string &s) const
TEST(IntegrationtestExecuteBrakeTest, testBrakeTestService)
static const std::string CONTROLLER_UNHOLD_MODE_SERVICE_NAME
Specifies the meaning of the holding registers.
static constexpr double WAIT_FOR_BRAKE_TEST_SERVICE_TIMEOUT_S