pre_deserialize.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2010, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /* Author: Josh Faust */
31 
32 /*
33  * Test PreDeserialize trait
34  */
35 
36 #include <gtest/gtest.h>
37 
38 #include <ros/ros.h>
39 
40 // To avoid the intraprocess optimization we use two messages
41 
43 {
44 };
45 
47 {
49  : touched(false)
50  {}
51 
52  bool touched;
53 };
54 
55 ROS_IMPLEMENT_SIMPLE_TOPIC_TRAITS(IncomingMsg, "my_md5sum", "test_roscpp_serialization/IncomingMsg", "\n");
56 ROS_IMPLEMENT_SIMPLE_TOPIC_TRAITS(OutgoingMsg, "my_md5sum", "test_roscpp_serialization/OutgoingMsg", "\n");
57 
58 namespace ros
59 {
60 
61 namespace serialization
62 {
63 template<>
65 {
66  template<typename Stream>
67  inline static void write(Stream&, const IncomingMsg&)
68  {
69  }
70 
71  template<typename Stream>
72  inline static void read(Stream&, IncomingMsg&)
73  {
74  }
75 
76  inline static uint32_t serializedLength(const IncomingMsg&)
77  {
78  return 0;
79  }
80 };
81 
82 template<>
84 {
85  template<typename Stream>
86  inline static void write(Stream&, const OutgoingMsg&)
87  {
88  }
89 
90  template<typename Stream>
91  inline static void read(Stream&, OutgoingMsg&)
92  {
93  }
94 
95  inline static uint32_t serializedLength(const OutgoingMsg&)
96  {
97  return 0;
98  }
99 };
100 
101 template<>
103 {
104  static void notify(const PreDeserializeParams<IncomingMsg>& params)
105  {
106  params.message->touched = true;
107  }
108 };
109 } // namespace serialization
110 } // namespace ros
111 
114 {
115  g_msg = msg;
116 }
117 
118 TEST(PreDeserialize, preDeserialize)
119 {
120  ros::NodeHandle nh;
121  ros::Publisher pub = nh.advertise<OutgoingMsg>("test", 0);
122  ros::Subscriber sub = nh.subscribe("test", 0, callback);
123 
124  pub.publish(OutgoingMsg());
125 
126  while (!g_msg)
127  {
128  ros::spinOnce();
129  ros::WallDuration(0.01).sleep();
130  }
131 
132  EXPECT_TRUE(g_msg->touched);
133 }
134 
135 int main(int argc, char** argv)
136 {
137  testing::InitGoogleTest(&argc, argv);
138  ros::init(argc, argv, "builtin_types");
139  ros::NodeHandle nh;
140 
141  return RUN_ALL_TESTS();
142 }
143 
144 
145 
146 
147 
int main(int argc, char **argv)
ROS_IMPLEMENT_SIMPLE_TOPIC_TRAITS(IncomingMsg,"my_md5sum","test_roscpp_serialization/IncomingMsg","\n")
static void write(Stream &, const OutgoingMsg &)
void publish(const boost::shared_ptr< M > &message) const
static void write(Stream &, const IncomingMsg &)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void callback(const boost::shared_ptr< IncomingMsg const > &msg)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static void notify(const PreDeserializeParams< IncomingMsg > &params)
static void read(Stream &, IncomingMsg &)
bool sleep() const
boost::shared_ptr< IncomingMsg const > g_msg
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static void read(Stream &, OutgoingMsg &)
static uint32_t serializedLength(const OutgoingMsg &)
TEST(PreDeserialize, preDeserialize)
ROSCPP_DECL void spinOnce()
static uint32_t serializedLength(const IncomingMsg &)


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:46