36 #include <gtest/gtest.h> 61 namespace serialization
66 template<
typename Stream>
71 template<
typename Stream>
85 template<
typename Stream>
90 template<
typename Stream>
106 params.
message->touched =
true;
118 TEST(PreDeserialize, preDeserialize)
132 EXPECT_TRUE(g_msg->touched);
135 int main(
int argc,
char** argv)
137 testing::InitGoogleTest(&argc, argv);
141 return RUN_ALL_TESTS();
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 > ¶ms)
static void read(Stream &, IncomingMsg &)
boost::shared_ptr< IncomingMsg const > g_msg
boost::shared_ptr< M > message
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 &)