4 #include <ram_msgs/AdditiveManufacturingTrajectory.h> 5 #include <ram_utils/UnmodifiedTrajectory.h> 7 #include <gtest/gtest.h> 9 std::unique_ptr<ros::NodeHandle>
nh;
13 TEST(TestSuite, testSrvExistence)
15 unmodified_trajectory_client =
nh->serviceClient<ram_utils::UnmodifiedTrajectory>(
16 "ram/buffer/get_unmodified_trajectory");
21 TEST(TestSuite, testVerifyTrajectoryNotInBuffer)
26 ram_utils::UnmodifiedTrajectory srv;
27 srv.request.generated = timestamp;
29 bool success(unmodified_trajectory_client.
call(srv));
30 EXPECT_FALSE(success);
33 TEST(TestSuite, testVerifyTrajectoryInBuffer)
35 ram_msgs::AdditiveManufacturingTrajectory
trajectory;
37 trajectory.generated = timestamp;
38 trajectory.modified = timestamp;
39 test_trajectory_pub.
publish(trajectory);
41 ram_utils::UnmodifiedTrajectory srv;
42 srv.request.generated = timestamp;
44 bool success(unmodified_trajectory_client.
call(srv));
51 ros::init(argc, argv,
"trajectory_utils_test_client");
53 test_trajectory_pub =
nh->advertise<ram_msgs::AdditiveManufacturingTrajectory>(
"ram/trajectory", 5,
true);
62 testing::InitGoogleTest(&argc, argv);
63 return RUN_ALL_TESTS();
void publish(const boost::shared_ptr< M > &message) const
ros::ServiceClient unmodified_trajectory_client
std::unique_ptr< ros::NodeHandle > nh
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
ram_msgs::AdditiveManufacturingTrajectory trajectory
int main(int argc, char **argv)
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
ros::Publisher test_trajectory_pub
TEST(TestSuite, testSrvExistence)
#define ROS_WARN_STREAM_THROTTLE(rate, args)
uint32_t getNumSubscribers() const
ROSCPP_DECL bool exists(const std::string &service_name, bool print_failure_reason)
std::string getTopic() const