27 #include <gtest/gtest.h>
33 TEST(CartesianStateHandleTest, TestConstructor)
35 std::string reference_frame =
"base";
36 std::string controlled_frame =
"tool0";
37 geometry_msgs::Pose pose_buffer;
38 geometry_msgs::Twist twist_buffer;
39 geometry_msgs::Accel accel_buffer;
40 geometry_msgs::Accel jerk_buffer;
42 EXPECT_NO_THROW(
CartesianStateHandle obj(reference_frame, controlled_frame, &pose_buffer, &twist_buffer,
43 &accel_buffer, &jerk_buffer));
45 CartesianStateHandle obj(reference_frame, controlled_frame,
nullptr, &twist_buffer, &accel_buffer, &jerk_buffer),
48 CartesianStateHandle obj(reference_frame, controlled_frame, &pose_buffer,
nullptr, &accel_buffer, &jerk_buffer),
51 CartesianStateHandle obj(reference_frame, controlled_frame, &pose_buffer, &twist_buffer,
nullptr, &jerk_buffer),
54 CartesianStateHandle obj(reference_frame, controlled_frame, &pose_buffer, &twist_buffer, &accel_buffer,
nullptr),
58 int main(
int argc,
char** argv)
60 testing::InitGoogleTest(&argc, argv);
61 return RUN_ALL_TESTS();