36 #include <gtest/gtest.h>
38 #include <sensor_msgs/JointState.h>
39 #include <std_msgs/Float64.h>
49 void positionCB(
const sensor_msgs::JointState& msg) {
53 bool waitToReachTarget(
double target, std::string& err,
double precision=5e-2,
double timeout=20.0) {
56 std_msgs::Float64
cmd;
62 if(std::fabs(target-
position) < precision)
65 err =
"Timed out, target = " + std::to_string(target) +
", current = " + std::to_string(
position);
71 err =
"ROS shutdwon, target = " + std::to_string(target) +
", current = " + std::to_string(
position);
88 EXPECT_TRUE(waitToReachTarget(1.0, err)) << err;
89 EXPECT_TRUE(waitToReachTarget(-1.0, err)) << err;
90 EXPECT_TRUE(waitToReachTarget(0.0, err)) << err;
94 int main(
int argc,
char** argv) {
95 testing::InitGoogleTest(&argc, argv);
99 int ret = RUN_ALL_TESTS();