test_shapeshifter.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2009, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage, Inc. nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 ********************************************************************/
34 
35 // Bring in my package's API, which is what I'm testing
36 #include "ros/ros.h"
38 #include "std_msgs/String.h"
39 #include "std_msgs/Int32.h"
40 
41 // Bring in gtest
42 #include <gtest/gtest.h>
43 
44 class ShapeShifterSubscriber : public testing::Test
45 {
46  public:
47 
48  bool success;
49 
51  {
52  try {
53  std_msgs::Int32::Ptr s = msg->instantiate<std_msgs::Int32>();
55  {
56  success = true;
57  }
58  }
59 
61  {
62  try {
63  std_msgs::String::Ptr s = msg->instantiate<std_msgs::String>();
64  if (s->data == "chatter")
65  success = true;
67  {
68 
69  }
70  }
71 
73  {
74  try {
75  std_msgs::String::Ptr s = msg->instantiate<std_msgs::String>();
76  printf("Got data: %s", s->data.c_str());
77  if (s->data == "abc123")
78  success = true;
80  {
81  printf("Instantiate failed!\n");
82  }
83  }
84 
85 protected:
87 
88  void SetUp()
89  {
90  success = false;
91  }
92 
93  void TearDown() {}
94 };
95 
96 
97 TEST_F(ShapeShifterSubscriber, testInstantiateString)
98 {
99  ros::NodeHandle nh;
101 
103 
104  while(ros::Time::now() < t1 && !success)
105  {
106  ros::WallDuration(0.01).sleep();
107  ros::spinOnce();
108  }
109 
111 
112  if(success)
113  SUCCEED();
114  else
115  FAIL();
116 }
117 
118 TEST_F(ShapeShifterSubscriber, testInstantiateInt)
119 {
120  ros::NodeHandle nh;
122 
124 
125  while(ros::Time::now() < t1 && !success)
126  {
127  ros::WallDuration(0.01).sleep();
128  ros::spinOnce();
129  }
130 
132 
133  if(success)
134  SUCCEED();
135  else
136  FAIL();
137 }
138 
140 {
141  ros::NodeHandle nh;
143 
145 
146  ros::Publisher pub = nh.advertise<std_msgs::String>("loopback", 1);
147  std_msgs::String s;
148  s.data = "abc123";
149  pub.publish(s);
150 
151  while(ros::Time::now() < t1 && !success)
152  {
153  ros::WallDuration(0.01).sleep();
154  ros::spinOnce();
155  }
156 
158 
159  if(success)
160  SUCCEED();
161  else
162  FAIL();
163 }
164 
165 int main(int argc, char **argv){
166  ros::init(argc, argv, "test_shapeshifter");
167 
168  testing::InitGoogleTest(&argc, argv);
169  return RUN_ALL_TESTS();
170 }
void messageCallbackString(const topic_tools::ShapeShifter::ConstPtr &msg)
TEST_F(ShapeShifterSubscriber, testInstantiateString)
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
XmlRpcServer s
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void messageCallbackLoopback(const topic_tools::ShapeShifter::ConstPtr &msg)
bool sleep() const
void messageCallbackInt(const topic_tools::ShapeShifter::ConstPtr &msg)
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static Time now()
ROSCPP_DECL void spinOnce()


topic_tools
Author(s): Morgan Quigley, Brian Gerkey
autogenerated on Sun Feb 3 2019 03:30:24