36 #include <gtest/gtest.h> 38 #include <sensor_msgs/JointState.h> 39 #include <std_msgs/Float64.h> 50 position = msg.position[0];
53 bool waitToReachTarget(
double target, std::string& err,
double precision=5e-2,
double timeout=20.0) {
54 position = 1e3*precision + target;
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);
79 pub = nh.
advertise<std_msgs::Float64>(
"position_controller/command", 1);
94 int main(
int argc,
char** argv) {
95 testing::InitGoogleTest(&argc, argv);
99 int ret = RUN_ALL_TESTS();
TEST_F(SimpleBotFixture, TestPosition)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool waitToReachTarget(double target, std::string &err, double precision=5e-2, double timeout=20.0)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void publish(const boost::shared_ptr< M > &message) const
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void positionCB(const sensor_msgs::JointState &msg)
ROSCPP_DECL void shutdown()