services_clients.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <ros/package.h>
3 
4 #include <ram_msgs/AdditiveManufacturingTrajectory.h>
5 #include <ram_trajectory_utils/UnmodifiedTrajectory.h>
6 
7 #include <gtest/gtest.h>
8 
9 std::unique_ptr<ros::NodeHandle> nh;
12 
13 TEST(TestSuite, testSrvExistence)
14 {
15  unmodified_trajectory_client = nh->serviceClient<ram_trajectory_utils::UnmodifiedTrajectory>(
16  "ram/buffer/get_unmodified_trajectory");
17  bool exists(unmodified_trajectory_client.waitForExistence(ros::Duration(1)));
18  EXPECT_TRUE(exists);
19 }
20 
21 TEST(TestSuite, testVerifyTrajectoryNotInBuffer)
22 {
23  ros::Time timestamp = ros::Time::now();
24 
25  // Service request
26  ram_trajectory_utils::UnmodifiedTrajectory srv;
27  srv.request.generated = timestamp;
28 
29  bool success(unmodified_trajectory_client.call(srv));
30  EXPECT_FALSE(success);
31 }
32 
33 TEST(TestSuite, testVerifyTrajectoryInBuffer)
34 {
35  ram_msgs::AdditiveManufacturingTrajectory trajectory;
36  ros::Time timestamp = ros::Time::now();
37  trajectory.generated = timestamp;
38  trajectory.modified = timestamp;
39  test_trajectory_pub.publish(trajectory);
40  // Service request
41  ram_trajectory_utils::UnmodifiedTrajectory srv;
42  srv.request.generated = timestamp;
43 
44  bool success(unmodified_trajectory_client.call(srv));
45  EXPECT_TRUE(success);
46 }
47 
48 int main(int argc,
49  char **argv)
50 {
51  ros::init(argc, argv, "trajectory_utils_test_client");
52  nh.reset(new ros::NodeHandle);
53  test_trajectory_pub = nh->advertise<ram_msgs::AdditiveManufacturingTrajectory>("ram/trajectory", 5, true);
54 
55  // Make sure we have at least one subscriber to this topic
56  while (test_trajectory_pub.getNumSubscribers() != 1)
57  {
58  ROS_WARN_STREAM_THROTTLE(1, test_trajectory_pub.getTopic() + " has zero subscriber, waiting...");
59  ros::Duration(0.1).sleep();
60  }
61 
62  testing::InitGoogleTest(&argc, argv);
63  return RUN_ALL_TESTS();
64 }
void publish(const boost::shared_ptr< M > &message) const
bool sleep() 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)
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
static Time now()
ROSCPP_DECL bool exists(const std::string &service_name, bool print_failure_reason)
std::string getTopic() const


ram_trajectory_utils
Author(s): Andres Campos - Institut Maupertuis
autogenerated on Fri Oct 27 2017 02:49:34