39 #include <gtest/gtest.h>
40 #include <rclcpp/rclcpp.hpp>
49 rclcpp::NodeOptions node_options;
50 node_options.automatically_declare_parameters_from_overrides(
true);
51 test_node_ = std::make_shared<rclcpp::Node>(
"move_group_param_test_node", node_options);
64 auto params_client = std::make_shared<rclcpp::SyncParametersClient>(test_node_,
"move_group");
65 bool reach_param_client = params_client->wait_for_service(std::chrono::seconds(5));
67 if (!reach_param_client)
69 RCLCPP_ERROR(test_node_->get_logger(),
"Couldn't reach parameter server. Is the move_group up and running?");
71 ASSERT_TRUE(reach_param_client);
78 bool param_exists =
false;
79 if (params_client->wait_for_service(std::chrono::milliseconds(1)))
81 param_exists = params_client->has_parameter(param_name);
84 RCLCPP_ERROR(test_node_->get_logger(),
"Parameter %s doesn't exists", param_name.c_str());
89 RCLCPP_ERROR(test_node_->get_logger(),
"Cannot read parameter %s because service couldn't be reached",
92 EXPECT_TRUE(param_exists);
98 int main(
int argc,
char** argv)
100 rclcpp::init(argc, argv);
101 ::testing::InitGoogleTest(&argc, argv);
102 int result = RUN_ALL_TESTS();
Test fixture to spin up a node to start a move group with.
std::shared_ptr< rclcpp::Node > test_node_
int main(int argc, char **argv)
TEST_F(MoveGroupFixture, testParamAPI)
const std::vector< std::string > PARAMETER_NAME_LIST