18 #include <gtest/gtest.h> 20 TEST(ChainManagerTests, test_rosparam_loading)
26 EXPECT_EQ(static_cast<size_t>(14), params.
free_params.size());
28 EXPECT_EQ(static_cast<size_t>(2), params.
free_frames.size());
29 EXPECT_EQ(
"head_camera_rgb_joint", params.
free_frames[0].name);
34 EXPECT_EQ(static_cast<size_t>(2), params.
models.size());
35 EXPECT_EQ(
"arm", params.
models[0].name);
36 EXPECT_EQ(
"chain", params.
models[0].type);
37 EXPECT_EQ(
"gripper_led_frame", static_cast<std::string>(params.
models[0].params[
"frame"]));
39 EXPECT_EQ(static_cast<size_t>(2), params.
error_blocks.size());
41 EXPECT_EQ(
"camera3d_to_arm", params.
error_blocks[0].type);
42 EXPECT_EQ(
"arm", static_cast<std::string>(params.
error_blocks[0].params[
"arm"]));
43 EXPECT_EQ(
"camera", static_cast<std::string>(params.
error_blocks[0].params[
"camera"]));
52 int main(
int argc,
char** argv)
54 ros::init(argc, argv,
"optimization_param_tests");
55 testing::InitGoogleTest(&argc, argv);
56 return RUN_ALL_TESTS();
Class to hold parameters for optimization.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::vector< FreeFrameInitialValue > free_frames_initial_values
TEST(ChainManagerTests, test_rosparam_loading)
std::vector< std::string > free_params
int main(int argc, char **argv)
bool LoadFromROS(ros::NodeHandle &nh)
std::vector< FreeFrameParams > free_frames
std::vector< Params > models
std::vector< Params > error_blocks