to ros_comm
This commit is contained in:
parent
d4dee63a9d
commit
6f0aed67d0
|
@ -1,27 +0,0 @@
|
||||||
cmake_minimum_required(VERSION 2.4.6)
|
|
||||||
include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
|
|
||||||
|
|
||||||
rosbuild_init()
|
|
||||||
|
|
||||||
#set the default path for built executables to the "bin" directory
|
|
||||||
set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
|
|
||||||
#set the default path for built libraries to the "lib" directory
|
|
||||||
set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
|
|
||||||
|
|
||||||
rosbuild_genmsg()
|
|
||||||
rosbuild_gensrv()
|
|
||||||
|
|
||||||
include_directories(include)
|
|
||||||
|
|
||||||
rosbuild_add_gtest(serialization src/serialization.cpp)
|
|
||||||
rosbuild_add_gtest(generated_messages src/generated_messages.cpp)
|
|
||||||
|
|
||||||
rosbuild_add_executable(builtin_types src/builtin_types.cpp)
|
|
||||||
rosbuild_declare_test(builtin_types)
|
|
||||||
rosbuild_add_gtest_build_flags(builtin_types)
|
|
||||||
rosbuild_add_rostest(test/builtin_types.test)
|
|
||||||
|
|
||||||
rosbuild_add_executable(pre_deserialize src/pre_deserialize.cpp)
|
|
||||||
rosbuild_declare_test(pre_deserialize)
|
|
||||||
rosbuild_add_gtest_build_flags(pre_deserialize)
|
|
||||||
rosbuild_add_rostest(test/pre_deserialize.test)
|
|
|
@ -1 +0,0 @@
|
||||||
include $(shell rospack find mk)/cmake.mk
|
|
|
@ -1,149 +0,0 @@
|
||||||
/*
|
|
||||||
* Copyright (c) 2009, Willow Garage, Inc.
|
|
||||||
* All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions are met:
|
|
||||||
*
|
|
||||||
* * Redistributions of source code must retain the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer.
|
|
||||||
* * Redistributions in binary form must reproduce the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer in the
|
|
||||||
* documentation and/or other materials provided with the distribution.
|
|
||||||
* * Neither the name of Willow Garage, Inc. nor the names of its
|
|
||||||
* contributors may be used to endorse or promote products derived from
|
|
||||||
* this software without specific prior written permission.
|
|
||||||
*
|
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
|
||||||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
|
||||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
|
||||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
|
|
||||||
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
|
||||||
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
|
||||||
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
|
||||||
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
|
||||||
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
|
||||||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
* POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#ifndef TEST_ROSCP_SERIALIZATION_HELPERS_H
|
|
||||||
#define TEST_ROSCP_SERIALIZATION_HELPERS_H
|
|
||||||
|
|
||||||
#include <boost/shared_array.hpp>
|
|
||||||
#include <ros/serialization.h>
|
|
||||||
|
|
||||||
namespace test_roscpp_serialization
|
|
||||||
{
|
|
||||||
namespace ser = ros::serialization;
|
|
||||||
namespace mt = ros::message_traits;
|
|
||||||
typedef boost::shared_array<uint8_t> Array;
|
|
||||||
|
|
||||||
template<typename T>
|
|
||||||
Array serializeAndDeserialize(const T& ser_val, T& deser_val)
|
|
||||||
{
|
|
||||||
uint32_t len = ser::serializationLength(ser_val);
|
|
||||||
boost::shared_array<uint8_t> b(new uint8_t[len]);
|
|
||||||
ser::OStream ostream(b.get(), len);
|
|
||||||
ser::serialize(ostream, ser_val);
|
|
||||||
ser::IStream istream(b.get(), len);
|
|
||||||
ser::deserialize(istream, deser_val);
|
|
||||||
|
|
||||||
return b;
|
|
||||||
}
|
|
||||||
|
|
||||||
template<class T> class Allocator;
|
|
||||||
|
|
||||||
// specialize for void:
|
|
||||||
template<>
|
|
||||||
class Allocator<void>
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
typedef void* pointer;
|
|
||||||
typedef const void* const_pointer;
|
|
||||||
// reference to void members are impossible.
|
|
||||||
typedef void value_type;
|
|
||||||
|
|
||||||
template<class U>
|
|
||||||
struct rebind
|
|
||||||
{
|
|
||||||
typedef Allocator<U> other;
|
|
||||||
};
|
|
||||||
};
|
|
||||||
|
|
||||||
template<class T>
|
|
||||||
class Allocator
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
typedef size_t size_type;
|
|
||||||
typedef ptrdiff_t difference_type;
|
|
||||||
typedef T* pointer;
|
|
||||||
typedef const T* const_pointer;
|
|
||||||
typedef T& reference;
|
|
||||||
typedef const T& const_reference;
|
|
||||||
typedef T value_type;
|
|
||||||
|
|
||||||
template<class U>
|
|
||||||
struct rebind
|
|
||||||
{
|
|
||||||
typedef Allocator<U> other;
|
|
||||||
};
|
|
||||||
|
|
||||||
Allocator() throw ()
|
|
||||||
{
|
|
||||||
}
|
|
||||||
template<class U>
|
|
||||||
Allocator(const Allocator<U>& u) throw ()
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
~Allocator() throw ()
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
pointer address(reference r) const
|
|
||||||
{
|
|
||||||
return &r;
|
|
||||||
}
|
|
||||||
const_pointer address(const_reference r) const
|
|
||||||
{
|
|
||||||
return &r;
|
|
||||||
}
|
|
||||||
size_type max_size() const throw ()
|
|
||||||
{
|
|
||||||
return ~size_type(0);
|
|
||||||
}
|
|
||||||
pointer allocate(size_type n, Allocator<void>::const_pointer hint = 0)
|
|
||||||
{
|
|
||||||
return reinterpret_cast<pointer> (malloc(n * sizeof(T)));
|
|
||||||
}
|
|
||||||
void deallocate(pointer p, size_type n)
|
|
||||||
{
|
|
||||||
free(p);
|
|
||||||
}
|
|
||||||
|
|
||||||
void construct(pointer p, const_reference val)
|
|
||||||
{
|
|
||||||
new (p) T(val);
|
|
||||||
}
|
|
||||||
void destroy(pointer p)
|
|
||||||
{
|
|
||||||
p->~T();
|
|
||||||
}
|
|
||||||
};
|
|
||||||
|
|
||||||
template<class T1, class T2>
|
|
||||||
inline bool operator==(const Allocator<T1>& a1, const Allocator<T2>& a2) throw ()
|
|
||||||
{
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
template<class T1, class T2>
|
|
||||||
inline bool operator!=(const Allocator<T1>& a1, const Allocator<T2>& a2) throw ()
|
|
||||||
{
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif // TEST_ROSCP_SERIALIZATION_HELPERS_H
|
|
|
@ -1,19 +0,0 @@
|
||||||
<package>
|
|
||||||
<description brief="Tests roscpp templated serialization and message generation">
|
|
||||||
Set of tests to test templated serialization, message generation, and using messages with custom allocators
|
|
||||||
|
|
||||||
</description>
|
|
||||||
<author>Josh Faust</author>
|
|
||||||
<license>BSD</license>
|
|
||||||
<review status="unreviewed" notes=""/>
|
|
||||||
<url>http://ros.org/wiki/test_roscpp_serialization</url>
|
|
||||||
<depend package="roscpp"/>
|
|
||||||
<depend package="roslib"/>
|
|
||||||
<depend package="std_msgs"/>
|
|
||||||
<platform os="ubuntu" version="9.04"/>
|
|
||||||
<platform os="ubuntu" version="9.10"/>
|
|
||||||
<platform os="ubuntu" version="10.04"/>
|
|
||||||
<platform os="macports" version="macports"/>
|
|
||||||
</package>
|
|
||||||
|
|
||||||
|
|
|
@ -1,2 +0,0 @@
|
||||||
# This comment has "quotes" in it
|
|
||||||
FixedLength[4] a
|
|
|
@ -1 +0,0 @@
|
||||||
VariableLength[4] a
|
|
|
@ -1,12 +0,0 @@
|
||||||
uint8 a = 1
|
|
||||||
int8 b = 2
|
|
||||||
uint16 c = 3
|
|
||||||
int16 d = 4
|
|
||||||
uint32 e = 5
|
|
||||||
int32 f = 6
|
|
||||||
uint64 g = 7
|
|
||||||
int64 h = 8
|
|
||||||
float32 fa = 1.5
|
|
||||||
float64 fb = 40.9
|
|
||||||
string str = hello there
|
|
||||||
string str2 = this string has "quotes" and \slashes\ in it
|
|
|
@ -1 +0,0 @@
|
||||||
uint32 a
|
|
|
@ -1 +0,0 @@
|
||||||
std_msgs/UInt8 a
|
|
|
@ -1 +0,0 @@
|
||||||
FixedLength a
|
|
|
@ -1 +0,0 @@
|
||||||
VariableLength a
|
|
|
@ -1,2 +0,0 @@
|
||||||
uint32 a
|
|
||||||
float32 b
|
|
|
@ -1,2 +0,0 @@
|
||||||
# This comment has "quotes" in it and \slashes\
|
|
||||||
roslib/Log[4] a
|
|
|
@ -1 +0,0 @@
|
||||||
string[5] foo
|
|
|
@ -1,2 +0,0 @@
|
||||||
int8 foo
|
|
||||||
Header header
|
|
|
@ -1 +0,0 @@
|
||||||
uint32[] a
|
|
|
@ -1,2 +0,0 @@
|
||||||
# This comment has "quotes" in it
|
|
||||||
roslib/Log[] a
|
|
|
@ -1 +0,0 @@
|
||||||
string[] foo
|
|
|
@ -1 +0,0 @@
|
||||||
duration my_duration
|
|
|
@ -1,2 +0,0 @@
|
||||||
Header header
|
|
||||||
uint32 a
|
|
|
@ -1,2 +0,0 @@
|
||||||
CustomHeader header
|
|
||||||
uint32 a
|
|
|
@ -1 +0,0 @@
|
||||||
time my_time
|
|
|
@ -1,101 +0,0 @@
|
||||||
/*
|
|
||||||
* Copyright (c) 2009, Willow Garage, Inc.
|
|
||||||
* All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions are met:
|
|
||||||
*
|
|
||||||
* * Redistributions of source code must retain the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer.
|
|
||||||
* * Redistributions in binary form must reproduce the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer in the
|
|
||||||
* documentation and/or other materials provided with the distribution.
|
|
||||||
* * Neither the name of Willow Garage, Inc. nor the names of its
|
|
||||||
* contributors may be used to endorse or promote products derived from
|
|
||||||
* this software without specific prior written permission.
|
|
||||||
*
|
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
|
||||||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
|
||||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
|
||||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
|
|
||||||
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
|
||||||
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
|
||||||
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
|
||||||
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
|
||||||
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
|
||||||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
* POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
*/
|
|
||||||
|
|
||||||
/* Author: Josh Faust */
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Test serialization templates
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <gtest/gtest.h>
|
|
||||||
|
|
||||||
#include <ros/ros.h>
|
|
||||||
#include <std_msgs/builtin_bool.h>
|
|
||||||
#include <std_msgs/builtin_double.h>
|
|
||||||
#include <std_msgs/builtin_float.h>
|
|
||||||
#include <std_msgs/builtin_int16.h>
|
|
||||||
#include <std_msgs/builtin_int32.h>
|
|
||||||
#include <std_msgs/builtin_int64.h>
|
|
||||||
#include <std_msgs/builtin_int8.h>
|
|
||||||
#include <std_msgs/builtin_string.h>
|
|
||||||
#include <std_msgs/builtin_uint16.h>
|
|
||||||
#include <std_msgs/builtin_uint32.h>
|
|
||||||
#include <std_msgs/builtin_uint64.h>
|
|
||||||
#include <std_msgs/builtin_uint8.h>
|
|
||||||
|
|
||||||
TEST(BuiltinTypes, advertise)
|
|
||||||
{
|
|
||||||
ros::NodeHandle nh;
|
|
||||||
nh.advertise<bool>("test_bool", 1);
|
|
||||||
nh.advertise<double>("test_double", 1);
|
|
||||||
nh.advertise<float>("test_float", 1);
|
|
||||||
nh.advertise<int16_t>("test_int16", 1);
|
|
||||||
nh.advertise<int32_t>("test_int32", 1);
|
|
||||||
nh.advertise<int64_t>("test_int64", 1);
|
|
||||||
nh.advertise<int8_t>("test_int8", 1);
|
|
||||||
nh.advertise<std::string>("test_string", 1);
|
|
||||||
nh.advertise<uint16_t>("test_uint16", 1);
|
|
||||||
nh.advertise<uint32_t>("test_uint32", 1);
|
|
||||||
nh.advertise<uint64_t>("test_uint64", 1);
|
|
||||||
nh.advertise<uint8_t>("test_uint8", 1);
|
|
||||||
}
|
|
||||||
|
|
||||||
template<typename T>
|
|
||||||
void callback(const boost::shared_ptr<T const>&)
|
|
||||||
{}
|
|
||||||
|
|
||||||
TEST(BuiltinTypes, subscribe)
|
|
||||||
{
|
|
||||||
ros::NodeHandle nh;
|
|
||||||
nh.subscribe("test_bool", 1, callback<bool>);
|
|
||||||
nh.subscribe("test_double", 1, callback<double>);
|
|
||||||
nh.subscribe("test_float", 1, callback<float>);
|
|
||||||
nh.subscribe("test_int16", 1, callback<int16_t>);
|
|
||||||
nh.subscribe("test_int32", 1, callback<int32_t>);
|
|
||||||
nh.subscribe("test_int64", 1, callback<int64_t>);
|
|
||||||
nh.subscribe("test_int8", 1, callback<int8_t>);
|
|
||||||
nh.subscribe("test_string", 1, callback<std::string>);
|
|
||||||
nh.subscribe("test_uint16", 1, callback<uint16_t>);
|
|
||||||
nh.subscribe("test_uint32", 1, callback<uint32_t>);
|
|
||||||
nh.subscribe("test_uint64", 1, callback<uint64_t>);
|
|
||||||
nh.subscribe("test_uint8", 1, callback<uint8_t>);
|
|
||||||
}
|
|
||||||
|
|
||||||
int main(int argc, char** argv)
|
|
||||||
{
|
|
||||||
testing::InitGoogleTest(&argc, argv);
|
|
||||||
ros::init(argc, argv, "builtin_types");
|
|
||||||
ros::NodeHandle nh;
|
|
||||||
|
|
||||||
return RUN_ALL_TESTS();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -1,291 +0,0 @@
|
||||||
/*
|
|
||||||
* Copyright (c) 2009, Willow Garage, Inc.
|
|
||||||
* All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions are met:
|
|
||||||
*
|
|
||||||
* * Redistributions of source code must retain the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer.
|
|
||||||
* * Redistributions in binary form must reproduce the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer in the
|
|
||||||
* documentation and/or other materials provided with the distribution.
|
|
||||||
* * Neither the name of Willow Garage, Inc. nor the names of its
|
|
||||||
* contributors may be used to endorse or promote products derived from
|
|
||||||
* this software without specific prior written permission.
|
|
||||||
*
|
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
|
||||||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
|
||||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
|
||||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
|
|
||||||
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
|
||||||
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
|
||||||
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
|
||||||
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
|
||||||
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
|
||||||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
* POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
*/
|
|
||||||
|
|
||||||
/* Author: Josh Faust */
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Test generated messages
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <gtest/gtest.h>
|
|
||||||
#include "test_roscpp_serialization/helpers.h"
|
|
||||||
#include "test_roscpp_serialization/ArrayOfFixedLength.h"
|
|
||||||
#include "test_roscpp_serialization/ArrayOfVariableLength.h"
|
|
||||||
#include "test_roscpp_serialization/EmbeddedFixedLength.h"
|
|
||||||
#include "test_roscpp_serialization/EmbeddedVariableLength.h"
|
|
||||||
#include "test_roscpp_serialization/FixedLength.h"
|
|
||||||
#include "test_roscpp_serialization/VariableLength.h"
|
|
||||||
#include "test_roscpp_serialization/WithHeader.h"
|
|
||||||
#include "test_roscpp_serialization/EmbeddedExternal.h"
|
|
||||||
#include "test_roscpp_serialization/WithTime.h"
|
|
||||||
#include "test_roscpp_serialization/WithDuration.h"
|
|
||||||
#include "test_roscpp_serialization/WithMemberNamedHeaderThatIsNotAHeader.h"
|
|
||||||
#include "test_roscpp_serialization/FixedLengthArrayOfExternal.h"
|
|
||||||
#include "test_roscpp_serialization/VariableLengthArrayOfExternal.h"
|
|
||||||
#include "test_roscpp_serialization/Constants.h"
|
|
||||||
#include "test_roscpp_serialization/VariableLengthStringArray.h"
|
|
||||||
#include "test_roscpp_serialization/FixedLengthStringArray.h"
|
|
||||||
#include "test_roscpp_serialization/HeaderNotFirstMember.h"
|
|
||||||
|
|
||||||
using namespace test_roscpp_serialization;
|
|
||||||
|
|
||||||
namespace test_roscpp_serialization
|
|
||||||
{
|
|
||||||
ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(ArrayOfFixedLength, MyArrayOfFixedLength, Allocator);
|
|
||||||
ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(ArrayOfVariableLength, MyArrayOfVariableLength, Allocator);
|
|
||||||
ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(EmbeddedFixedLength, MyEmbeddedFixedLength, Allocator);
|
|
||||||
ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(EmbeddedVariableLength, MyEmbeddedVariableLength, Allocator);
|
|
||||||
ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(FixedLength, MyFixedLength, Allocator);
|
|
||||||
ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(VariableLength, MyVariableLength, Allocator);
|
|
||||||
ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(WithHeader, MyWithHeader, Allocator);
|
|
||||||
ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(EmbeddedExternal, MyEmbeddedExternal, Allocator);
|
|
||||||
ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(WithTime, MyWithTime, Allocator);
|
|
||||||
ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(WithDuration, MyWithDuration, Allocator);
|
|
||||||
ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(WithMemberNamedHeaderThatIsNotAHeader, MyWithMemberNamedHeaderThatIsNotAHeader, Allocator);
|
|
||||||
ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(FixedLengthArrayOfExternal, MyFixedLengthArrayOfExternal, Allocator);
|
|
||||||
ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(VariableLengthArrayOfExternal, MyVariableLengthArrayOfExternal, Allocator);
|
|
||||||
ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(FixedLengthStringArray, MyFixedLengthStringArray, Allocator);
|
|
||||||
ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(VariableLengthStringArray, MyVariableLengthStringArray, Allocator);
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(GeneratedMessages, traitsWithStandardMessages)
|
|
||||||
{
|
|
||||||
EXPECT_TRUE(mt::isFixedSize<ArrayOfFixedLength>());
|
|
||||||
EXPECT_FALSE(mt::isFixedSize<ArrayOfVariableLength>());
|
|
||||||
EXPECT_TRUE(mt::isFixedSize<EmbeddedFixedLength>());
|
|
||||||
EXPECT_FALSE(mt::isFixedSize<EmbeddedVariableLength>());
|
|
||||||
EXPECT_TRUE(mt::isFixedSize<FixedLength>());
|
|
||||||
EXPECT_FALSE(mt::isFixedSize<VariableLength>());
|
|
||||||
EXPECT_FALSE(mt::isFixedSize<WithHeader>());
|
|
||||||
EXPECT_TRUE(mt::isFixedSize<EmbeddedExternal>());
|
|
||||||
EXPECT_TRUE(mt::isFixedSize<WithTime>());
|
|
||||||
EXPECT_TRUE(mt::isFixedSize<WithDuration>());
|
|
||||||
EXPECT_TRUE(mt::isFixedSize<WithMemberNamedHeaderThatIsNotAHeader>());
|
|
||||||
EXPECT_FALSE(mt::isFixedSize<FixedLengthArrayOfExternal>());
|
|
||||||
EXPECT_FALSE(mt::isFixedSize<VariableLengthArrayOfExternal>());
|
|
||||||
EXPECT_FALSE(mt::isFixedSize<FixedLengthStringArray>());
|
|
||||||
EXPECT_FALSE(mt::isFixedSize<VariableLengthStringArray>());
|
|
||||||
|
|
||||||
EXPECT_FALSE(mt::hasHeader<ArrayOfFixedLength>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<ArrayOfVariableLength>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<EmbeddedFixedLength>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<EmbeddedVariableLength>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<FixedLength>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<VariableLength>());
|
|
||||||
EXPECT_TRUE(mt::hasHeader<WithHeader>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<EmbeddedExternal>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<WithTime>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<WithDuration>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<WithMemberNamedHeaderThatIsNotAHeader>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<FixedLengthArrayOfExternal>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<VariableLengthArrayOfExternal>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<FixedLengthStringArray>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<VariableLengthStringArray>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<HeaderNotFirstMember>());
|
|
||||||
|
|
||||||
EXPECT_FALSE(mt::isSimple<ArrayOfFixedLength>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<ArrayOfVariableLength>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<EmbeddedFixedLength>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<EmbeddedVariableLength>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<FixedLength>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<VariableLength>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<WithHeader>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<EmbeddedExternal>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<WithTime>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<WithDuration>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<WithMemberNamedHeaderThatIsNotAHeader>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<FixedLengthArrayOfExternal>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<VariableLengthArrayOfExternal>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<FixedLengthStringArray>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<VariableLengthStringArray>());
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(GeneratedMessages, traitsWithCustomAllocator)
|
|
||||||
{
|
|
||||||
EXPECT_TRUE(mt::isFixedSize<MyArrayOfFixedLength>());
|
|
||||||
EXPECT_FALSE(mt::isFixedSize<MyArrayOfVariableLength>());
|
|
||||||
EXPECT_TRUE(mt::isFixedSize<MyEmbeddedFixedLength>());
|
|
||||||
EXPECT_FALSE(mt::isFixedSize<MyEmbeddedVariableLength>());
|
|
||||||
EXPECT_TRUE(mt::isFixedSize<MyFixedLength>());
|
|
||||||
EXPECT_FALSE(mt::isFixedSize<MyVariableLength>());
|
|
||||||
EXPECT_FALSE(mt::isFixedSize<MyWithHeader>());
|
|
||||||
EXPECT_TRUE(mt::isFixedSize<MyEmbeddedExternal>());
|
|
||||||
EXPECT_TRUE(mt::isFixedSize<MyWithTime>());
|
|
||||||
EXPECT_TRUE(mt::isFixedSize<MyWithDuration>());
|
|
||||||
EXPECT_TRUE(mt::isFixedSize<MyWithMemberNamedHeaderThatIsNotAHeader>());
|
|
||||||
EXPECT_FALSE(mt::isFixedSize<MyFixedLengthArrayOfExternal>());
|
|
||||||
EXPECT_FALSE(mt::isFixedSize<MyVariableLengthArrayOfExternal>());
|
|
||||||
EXPECT_FALSE(mt::isFixedSize<MyFixedLengthStringArray>());
|
|
||||||
EXPECT_FALSE(mt::isFixedSize<MyVariableLengthStringArray>());
|
|
||||||
|
|
||||||
EXPECT_FALSE(mt::hasHeader<MyArrayOfFixedLength>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<MyArrayOfVariableLength>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<MyEmbeddedFixedLength>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<MyEmbeddedVariableLength>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<MyFixedLength>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<MyVariableLength>());
|
|
||||||
EXPECT_TRUE(mt::hasHeader<MyWithHeader>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<MyEmbeddedExternal>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<MyWithTime>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<MyWithDuration>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<MyWithMemberNamedHeaderThatIsNotAHeader>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<MyFixedLengthArrayOfExternal>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<MyVariableLengthArrayOfExternal>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<MyFixedLengthStringArray>());
|
|
||||||
EXPECT_FALSE(mt::hasHeader<MyVariableLengthStringArray>());
|
|
||||||
|
|
||||||
EXPECT_FALSE(mt::isSimple<MyArrayOfFixedLength>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<MyArrayOfVariableLength>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<MyEmbeddedFixedLength>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<MyEmbeddedVariableLength>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<MyFixedLength>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<MyVariableLength>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<MyWithHeader>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<MyEmbeddedExternal>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<MyWithTime>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<MyWithDuration>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<MyWithMemberNamedHeaderThatIsNotAHeader>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<MyFixedLengthArrayOfExternal>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<MyVariableLengthArrayOfExternal>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<MyFixedLengthStringArray>());
|
|
||||||
EXPECT_FALSE(mt::isSimple<MyVariableLengthStringArray>());
|
|
||||||
}
|
|
||||||
|
|
||||||
#define SERIALIZATION_COMPILATION_TEST(Type) \
|
|
||||||
TEST(GeneratedMessages, serialization_##Type) \
|
|
||||||
{ \
|
|
||||||
Type ser_val, deser_val; \
|
|
||||||
serializeAndDeserialize(ser_val, deser_val); \
|
|
||||||
}
|
|
||||||
|
|
||||||
SERIALIZATION_COMPILATION_TEST(ArrayOfFixedLength);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(ArrayOfVariableLength);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(EmbeddedFixedLength);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(EmbeddedVariableLength);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(FixedLength);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(VariableLength);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(WithHeader);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(EmbeddedExternal);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(WithTime);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(WithDuration);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(WithMemberNamedHeaderThatIsNotAHeader);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(FixedLengthArrayOfExternal);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(VariableLengthArrayOfExternal);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(FixedLengthStringArray);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(VariableLengthStringArray);
|
|
||||||
|
|
||||||
SERIALIZATION_COMPILATION_TEST(MyArrayOfFixedLength);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(MyArrayOfVariableLength);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(MyEmbeddedFixedLength);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(MyEmbeddedVariableLength);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(MyFixedLength);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(MyVariableLength);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(MyWithHeader);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(MyEmbeddedExternal);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(MyWithTime);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(MyWithDuration);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(MyWithMemberNamedHeaderThatIsNotAHeader);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(MyFixedLengthArrayOfExternal);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(MyVariableLengthArrayOfExternal);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(MyFixedLengthStringArray);
|
|
||||||
SERIALIZATION_COMPILATION_TEST(MyVariableLengthStringArray);
|
|
||||||
|
|
||||||
#define ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(Type, Allocator) \
|
|
||||||
TEST(GeneratedMessages, allocationConstructor_##Type) \
|
|
||||||
{ \
|
|
||||||
Allocator a; \
|
|
||||||
Type val(a); \
|
|
||||||
}
|
|
||||||
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(ArrayOfFixedLength, std::allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(ArrayOfVariableLength, std::allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(EmbeddedFixedLength, std::allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(EmbeddedVariableLength, std::allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(FixedLength, std::allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(VariableLength, std::allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(WithHeader, std::allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(EmbeddedExternal, std::allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(WithTime, std::allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(WithDuration, std::allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(WithMemberNamedHeaderThatIsNotAHeader, std::allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(FixedLengthArrayOfExternal, std::allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(VariableLengthArrayOfExternal, std::allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(FixedLengthStringArray, std::allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(VariableLengthStringArray, std::allocator<void>);
|
|
||||||
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(MyArrayOfFixedLength, Allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(MyArrayOfVariableLength, Allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(MyEmbeddedFixedLength, Allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(MyEmbeddedVariableLength, Allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(MyFixedLength, Allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(MyVariableLength, Allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(MyWithHeader, Allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(MyEmbeddedExternal, Allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(MyWithTime, Allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(MyWithDuration, Allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(MyWithMemberNamedHeaderThatIsNotAHeader, Allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(MyFixedLengthArrayOfExternal, Allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(MyVariableLengthArrayOfExternal, Allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(MyFixedLengthStringArray, Allocator<void>);
|
|
||||||
ALLOCATOR_CONSTRUCTOR_COMPILATION_TEST(MyVariableLengthStringArray, Allocator<void>);
|
|
||||||
|
|
||||||
TEST(Generated, serializationOStreamOperator)
|
|
||||||
{
|
|
||||||
using namespace ros::serialization;
|
|
||||||
Array b(new uint8_t[8]);
|
|
||||||
OStream ostream(b.get(), 8);
|
|
||||||
FixedLength m;
|
|
||||||
ostream << m;
|
|
||||||
ASSERT_EQ(ostream.getLength(), 0UL);
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(Generated, constants)
|
|
||||||
{
|
|
||||||
EXPECT_EQ(Constants::a, 1U);
|
|
||||||
EXPECT_EQ(Constants::b, 2);
|
|
||||||
EXPECT_EQ(Constants::c, 3U);
|
|
||||||
EXPECT_EQ(Constants::d, 4);
|
|
||||||
EXPECT_EQ(Constants::e, 5U);
|
|
||||||
EXPECT_EQ(Constants::f, 6);
|
|
||||||
EXPECT_EQ(Constants::g, 7U);
|
|
||||||
EXPECT_EQ(Constants::h, 8);
|
|
||||||
EXPECT_FLOAT_EQ(Constants::fa, 1.5);
|
|
||||||
EXPECT_FLOAT_EQ(Constants::fb, 40.9);
|
|
||||||
EXPECT_STREQ(Constants::str.c_str(), "hello there");
|
|
||||||
EXPECT_STREQ(Constants::str2.c_str(), "this string has \"quotes\" and \\slashes\\ in it");
|
|
||||||
}
|
|
||||||
|
|
||||||
int main(int argc, char** argv)
|
|
||||||
{
|
|
||||||
testing::InitGoogleTest(&argc, argv);
|
|
||||||
return RUN_ALL_TESTS();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -1,147 +0,0 @@
|
||||||
/*
|
|
||||||
* Copyright (c) 2010, Willow Garage, Inc.
|
|
||||||
* All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions are met:
|
|
||||||
*
|
|
||||||
* * Redistributions of source code must retain the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer.
|
|
||||||
* * Redistributions in binary form must reproduce the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer in the
|
|
||||||
* documentation and/or other materials provided with the distribution.
|
|
||||||
* * Neither the name of Willow Garage, Inc. nor the names of its
|
|
||||||
* contributors may be used to endorse or promote products derived from
|
|
||||||
* this software without specific prior written permission.
|
|
||||||
*
|
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
|
||||||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
|
||||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
|
||||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
|
|
||||||
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
|
||||||
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
|
||||||
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
|
||||||
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
|
||||||
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
|
||||||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
* POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
*/
|
|
||||||
|
|
||||||
/* Author: Josh Faust */
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Test PreDeserialize trait
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <gtest/gtest.h>
|
|
||||||
|
|
||||||
#include <ros/ros.h>
|
|
||||||
|
|
||||||
// To avoid the intraprocess optimization we use two messages
|
|
||||||
|
|
||||||
struct OutgoingMsg
|
|
||||||
{
|
|
||||||
};
|
|
||||||
|
|
||||||
struct IncomingMsg
|
|
||||||
{
|
|
||||||
IncomingMsg()
|
|
||||||
: touched(false)
|
|
||||||
{}
|
|
||||||
|
|
||||||
bool touched;
|
|
||||||
};
|
|
||||||
|
|
||||||
ROS_IMPLEMENT_SIMPLE_TOPIC_TRAITS(IncomingMsg, "my_md5sum", "test_roscpp_serialization/IncomingMsg", "\n");
|
|
||||||
ROS_IMPLEMENT_SIMPLE_TOPIC_TRAITS(OutgoingMsg, "my_md5sum", "test_roscpp_serialization/OutgoingMsg", "\n");
|
|
||||||
|
|
||||||
namespace ros
|
|
||||||
{
|
|
||||||
|
|
||||||
namespace serialization
|
|
||||||
{
|
|
||||||
template<>
|
|
||||||
struct Serializer<IncomingMsg>
|
|
||||||
{
|
|
||||||
template<typename Stream>
|
|
||||||
inline static void write(Stream& stream, const IncomingMsg& v)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
template<typename Stream>
|
|
||||||
inline static void read(Stream& stream, IncomingMsg& v)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
inline static uint32_t serializedLength(const IncomingMsg& v)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
};
|
|
||||||
|
|
||||||
template<>
|
|
||||||
struct Serializer<OutgoingMsg>
|
|
||||||
{
|
|
||||||
template<typename Stream>
|
|
||||||
inline static void write(Stream& stream, const OutgoingMsg& v)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
template<typename Stream>
|
|
||||||
inline static void read(Stream& stream, OutgoingMsg& v)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
inline static uint32_t serializedLength(const OutgoingMsg& v)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
};
|
|
||||||
|
|
||||||
template<>
|
|
||||||
struct PreDeserialize<IncomingMsg>
|
|
||||||
{
|
|
||||||
static void notify(const PreDeserializeParams<IncomingMsg>& params)
|
|
||||||
{
|
|
||||||
params.message->touched = true;
|
|
||||||
}
|
|
||||||
};
|
|
||||||
} // namespace serialization
|
|
||||||
} // namespace ros
|
|
||||||
|
|
||||||
boost::shared_ptr<IncomingMsg const> g_msg;
|
|
||||||
void callback(const boost::shared_ptr<IncomingMsg const>& msg)
|
|
||||||
{
|
|
||||||
g_msg = msg;
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(PreDeserialize, preDeserialize)
|
|
||||||
{
|
|
||||||
ros::NodeHandle nh;
|
|
||||||
ros::Publisher pub = nh.advertise<OutgoingMsg>("test", 0);
|
|
||||||
ros::Subscriber sub = nh.subscribe("test", 0, callback);
|
|
||||||
|
|
||||||
pub.publish(OutgoingMsg());
|
|
||||||
|
|
||||||
while (!g_msg)
|
|
||||||
{
|
|
||||||
ros::spinOnce();
|
|
||||||
ros::WallDuration(0.01).sleep();
|
|
||||||
}
|
|
||||||
|
|
||||||
EXPECT_TRUE(g_msg->touched);
|
|
||||||
}
|
|
||||||
|
|
||||||
int main(int argc, char** argv)
|
|
||||||
{
|
|
||||||
testing::InitGoogleTest(&argc, argv);
|
|
||||||
ros::init(argc, argv, "builtin_types");
|
|
||||||
ros::NodeHandle nh;
|
|
||||||
|
|
||||||
return RUN_ALL_TESTS();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -1,477 +0,0 @@
|
||||||
/*
|
|
||||||
* Copyright (c) 2009, Willow Garage, Inc.
|
|
||||||
* All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions are met:
|
|
||||||
*
|
|
||||||
* * Redistributions of source code must retain the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer.
|
|
||||||
* * Redistributions in binary form must reproduce the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer in the
|
|
||||||
* documentation and/or other materials provided with the distribution.
|
|
||||||
* * Neither the name of Willow Garage, Inc. nor the names of its
|
|
||||||
* contributors may be used to endorse or promote products derived from
|
|
||||||
* this software without specific prior written permission.
|
|
||||||
*
|
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
|
||||||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
|
||||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
|
||||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
|
|
||||||
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
|
||||||
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
|
||||||
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
|
||||||
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
|
||||||
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
|
||||||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
* POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
*/
|
|
||||||
|
|
||||||
/* Author: Josh Faust */
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Test serialization templates
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <gtest/gtest.h>
|
|
||||||
#include <ros/static_assert.h>
|
|
||||||
#include <roslib/Header.h>
|
|
||||||
#include "test_roscpp_serialization/helpers.h"
|
|
||||||
|
|
||||||
using namespace ros;
|
|
||||||
using namespace ros::serialization;
|
|
||||||
using namespace test_roscpp_serialization;
|
|
||||||
|
|
||||||
ROS_STATIC_ASSERT(sizeof(ros::Time) == 8);
|
|
||||||
ROS_STATIC_ASSERT(sizeof(ros::Duration) == 8);
|
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
|
||||||
// Tests for compilation/validity of serialization/deserialization of primitive types
|
|
||||||
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
|
||||||
|
|
||||||
#define PRIMITIVE_SERIALIZATION_TEST(Type, SerInit, DeserInit) \
|
|
||||||
TEST(Serialization, Type) \
|
|
||||||
{ \
|
|
||||||
Type ser_val SerInit; \
|
|
||||||
Type deser_val DeserInit; \
|
|
||||||
Array b = serializeAndDeserialize(ser_val, deser_val); \
|
|
||||||
EXPECT_EQ(*(Type*)b.get(), ser_val); \
|
|
||||||
EXPECT_EQ(ser_val, deser_val); \
|
|
||||||
}
|
|
||||||
|
|
||||||
PRIMITIVE_SERIALIZATION_TEST(uint8_t, (5), (0));
|
|
||||||
PRIMITIVE_SERIALIZATION_TEST(int8_t, (5), (0));
|
|
||||||
PRIMITIVE_SERIALIZATION_TEST(uint16_t, (5), (0));
|
|
||||||
PRIMITIVE_SERIALIZATION_TEST(int16_t, (5), (0));
|
|
||||||
PRIMITIVE_SERIALIZATION_TEST(uint32_t, (5), (0));
|
|
||||||
PRIMITIVE_SERIALIZATION_TEST(int32_t, (5), (0));
|
|
||||||
PRIMITIVE_SERIALIZATION_TEST(uint64_t, (5), (0));
|
|
||||||
PRIMITIVE_SERIALIZATION_TEST(int64_t, (5), (0));
|
|
||||||
PRIMITIVE_SERIALIZATION_TEST(float, (5.0f), (0.0f));
|
|
||||||
PRIMITIVE_SERIALIZATION_TEST(double, (5.0), (0.0));
|
|
||||||
PRIMITIVE_SERIALIZATION_TEST(Time, (500, 10000), (0, 0));
|
|
||||||
PRIMITIVE_SERIALIZATION_TEST(Duration, (500, 10000), (0, 0));
|
|
||||||
|
|
||||||
#define PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(Type, Start, Increment) \
|
|
||||||
TEST(Serialization, variableLengthArray_##Type) \
|
|
||||||
{ \
|
|
||||||
std::vector<Type> ser_val, deser_val; \
|
|
||||||
Type val = Start; \
|
|
||||||
for (uint32_t i = 0; i < 8; ++i) \
|
|
||||||
{ \
|
|
||||||
ser_val.push_back(val); \
|
|
||||||
val = val + Increment; \
|
|
||||||
} \
|
|
||||||
\
|
|
||||||
Array b = serializeAndDeserialize(ser_val, deser_val); \
|
|
||||||
EXPECT_TRUE(ser_val == deser_val); \
|
|
||||||
\
|
|
||||||
EXPECT_EQ(*(uint32_t*)b.get(), (uint32_t)ser_val.size()); \
|
|
||||||
for(size_t i = 0; i < ser_val.size(); ++i) \
|
|
||||||
{ \
|
|
||||||
Type* ptr = ((Type*)(b.get() + 4)) + i; \
|
|
||||||
EXPECT_EQ(*ptr, ser_val[i]); \
|
|
||||||
} \
|
|
||||||
}
|
|
||||||
|
|
||||||
PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(uint8_t, 65, 1);
|
|
||||||
PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(int8_t, 65, 1);
|
|
||||||
PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(uint16_t, 0, 100);
|
|
||||||
PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(int16_t, 0, 100);
|
|
||||||
PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(uint32_t, 0, 100);
|
|
||||||
PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(int32_t, 0, 100);
|
|
||||||
PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(uint64_t, 0, 100);
|
|
||||||
PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(int64_t, 0, 100);
|
|
||||||
PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(float, 0.0f, 100.0f);
|
|
||||||
PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(double, 0.0, 100.0);
|
|
||||||
PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(Time, Time(), Duration(100));
|
|
||||||
PRIMITIVE_VARIABLE_LENGTH_ARRAY_TEST(Duration, Duration(), Duration(100));
|
|
||||||
|
|
||||||
#define PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(Type, Start, Increment) \
|
|
||||||
TEST(Serialization, fixedLengthArray_##Type) \
|
|
||||||
{ \
|
|
||||||
boost::array<Type, 8> ser_val, deser_val; \
|
|
||||||
Type val = Start; \
|
|
||||||
for (uint32_t i = 0; i < 8; ++i) \
|
|
||||||
{ \
|
|
||||||
ser_val[i] = val; \
|
|
||||||
val = val + Increment; \
|
|
||||||
} \
|
|
||||||
\
|
|
||||||
Array b = serializeAndDeserialize(ser_val, deser_val); \
|
|
||||||
EXPECT_TRUE(ser_val == deser_val); \
|
|
||||||
\
|
|
||||||
for(size_t i = 0; i < ser_val.size(); ++i) \
|
|
||||||
{ \
|
|
||||||
Type* ptr = ((Type*)b.get()) + i; \
|
|
||||||
EXPECT_EQ(*ptr, ser_val[i]); \
|
|
||||||
} \
|
|
||||||
}
|
|
||||||
|
|
||||||
PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(uint8_t, 65, 1);
|
|
||||||
PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(int8_t, 65, 1);
|
|
||||||
PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(uint16_t, 0, 100);
|
|
||||||
PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(int16_t, 0, 100);
|
|
||||||
PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(uint32_t, 0, 100);
|
|
||||||
PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(int32_t, 0, 100);
|
|
||||||
PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(uint64_t, 0, 100);
|
|
||||||
PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(int64_t, 0, 100);
|
|
||||||
PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(float, 0.0f, 100.0f);
|
|
||||||
PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(double, 0.0, 100.0);
|
|
||||||
PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(Time, Time(), Duration(100));
|
|
||||||
PRIMITIVE_FIXED_LENGTH_ARRAY_TEST(Duration, Duration(), Duration(100));
|
|
||||||
|
|
||||||
TEST(Serialization, string)
|
|
||||||
{
|
|
||||||
std::string ser_val = "hello world";
|
|
||||||
std::string deser_val;
|
|
||||||
Array b = serializeAndDeserialize(ser_val, deser_val);
|
|
||||||
EXPECT_STREQ(ser_val.c_str(), deser_val.c_str());
|
|
||||||
|
|
||||||
EXPECT_EQ(*(uint32_t*)b.get(), (uint32_t)ser_val.size());
|
|
||||||
EXPECT_EQ(memcmp(b.get() + 4, ser_val.data(), ser_val.size()), 0);
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(Serialization, variableLengthArray_string)
|
|
||||||
{
|
|
||||||
std::vector<std::string> ser_val, deser_val;
|
|
||||||
ser_val.push_back("hello world");
|
|
||||||
ser_val.push_back("hello world22");
|
|
||||||
ser_val.push_back("hello world333");
|
|
||||||
ser_val.push_back("hello world4444");
|
|
||||||
ser_val.push_back("hello world55555");
|
|
||||||
Array b = serializeAndDeserialize(ser_val, deser_val);
|
|
||||||
EXPECT_TRUE(ser_val == deser_val);
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(Serialization, fixedLengthArray_string)
|
|
||||||
{
|
|
||||||
boost::array<std::string, 5> ser_val, deser_val;
|
|
||||||
ser_val[0] = "hello world";
|
|
||||||
ser_val[1] = "hello world22";
|
|
||||||
ser_val[2] = "hello world333";
|
|
||||||
ser_val[3] = "hello world4444";
|
|
||||||
ser_val[4] = "hello world55555";
|
|
||||||
Array b = serializeAndDeserialize(ser_val, deser_val);
|
|
||||||
EXPECT_TRUE(ser_val == deser_val);
|
|
||||||
}
|
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////////////////
|
|
||||||
// Test custom types and traits
|
|
||||||
////////////////////////////////////////////////////////////////////////////////////////////
|
|
||||||
|
|
||||||
// Class used to make sure fixed-size simple structs use a memcpy when serializing an array of them
|
|
||||||
// serialization only serializes a, memcpy will get both a and b.
|
|
||||||
struct FixedSizeSimple
|
|
||||||
{
|
|
||||||
FixedSizeSimple()
|
|
||||||
: a(0)
|
|
||||||
, b(0)
|
|
||||||
{}
|
|
||||||
|
|
||||||
int32_t a;
|
|
||||||
int32_t b;
|
|
||||||
};
|
|
||||||
|
|
||||||
namespace ros
|
|
||||||
{
|
|
||||||
namespace message_traits
|
|
||||||
{
|
|
||||||
template<> struct IsFixedSize<FixedSizeSimple> : public TrueType {};
|
|
||||||
template<> struct IsSimple<FixedSizeSimple> : public TrueType {};
|
|
||||||
} // namespace message_traits
|
|
||||||
|
|
||||||
namespace serialization
|
|
||||||
{
|
|
||||||
template<>
|
|
||||||
struct Serializer<FixedSizeSimple>
|
|
||||||
{
|
|
||||||
template<typename Stream>
|
|
||||||
inline static void write(Stream& stream, const FixedSizeSimple& v)
|
|
||||||
{
|
|
||||||
serialize(stream, v.a);
|
|
||||||
}
|
|
||||||
|
|
||||||
template<typename Stream>
|
|
||||||
inline static void read(Stream& stream, FixedSizeSimple& v)
|
|
||||||
{
|
|
||||||
deserialize(stream, v.a);
|
|
||||||
}
|
|
||||||
|
|
||||||
inline static uint32_t serializedLength(const FixedSizeSimple& v)
|
|
||||||
{
|
|
||||||
return 4;
|
|
||||||
}
|
|
||||||
};
|
|
||||||
} // namespace serialization
|
|
||||||
} // namespace ros
|
|
||||||
|
|
||||||
TEST(Serialization, fixedSizeSimple_vector)
|
|
||||||
{
|
|
||||||
{
|
|
||||||
FixedSizeSimple in, out;
|
|
||||||
in.a = 1;
|
|
||||||
in.b = 1;
|
|
||||||
|
|
||||||
serializeAndDeserialize(in, out);
|
|
||||||
ASSERT_EQ(out.a, 1);
|
|
||||||
ASSERT_EQ(out.b, 0);
|
|
||||||
}
|
|
||||||
|
|
||||||
{
|
|
||||||
std::vector<FixedSizeSimple> in, out;
|
|
||||||
in.resize(1);
|
|
||||||
in[0].a = 1;
|
|
||||||
in[0].b = 1;
|
|
||||||
|
|
||||||
serializeAndDeserialize(in, out);
|
|
||||||
ASSERT_EQ(out[0].a, 1);
|
|
||||||
ASSERT_EQ(out[0].b, 1);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(Serialization, fixedSizeSimple_array)
|
|
||||||
{
|
|
||||||
boost::array<FixedSizeSimple, 2> in, out;
|
|
||||||
in[0].a = 1;
|
|
||||||
in[0].b = 1;
|
|
||||||
|
|
||||||
serializeAndDeserialize(in, out);
|
|
||||||
ASSERT_EQ(out[0].a, 1);
|
|
||||||
ASSERT_EQ(out[0].b, 1);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Class used to make sure fixed-size non-simple structs only query the length of the first element
|
|
||||||
// in an array.
|
|
||||||
struct FixedSizeNonSimple
|
|
||||||
{
|
|
||||||
FixedSizeNonSimple()
|
|
||||||
: length_to_report(4)
|
|
||||||
{}
|
|
||||||
|
|
||||||
int32_t length_to_report;
|
|
||||||
};
|
|
||||||
|
|
||||||
namespace ros
|
|
||||||
{
|
|
||||||
namespace message_traits
|
|
||||||
{
|
|
||||||
template<> struct IsFixedSize<FixedSizeNonSimple> : public TrueType {};
|
|
||||||
} // namespace message_traits
|
|
||||||
|
|
||||||
namespace serialization
|
|
||||||
{
|
|
||||||
template<>
|
|
||||||
struct Serializer<FixedSizeNonSimple>
|
|
||||||
{
|
|
||||||
inline static uint32_t serializedLength(const FixedSizeNonSimple& v)
|
|
||||||
{
|
|
||||||
return v.length_to_report;
|
|
||||||
}
|
|
||||||
};
|
|
||||||
} // namespace serialization
|
|
||||||
} // namespace ros
|
|
||||||
|
|
||||||
TEST(Serialization, fixedSizeNonSimple_vector)
|
|
||||||
{
|
|
||||||
std::vector<FixedSizeNonSimple> in;
|
|
||||||
in.resize(2);
|
|
||||||
in[1].length_to_report = 100;
|
|
||||||
|
|
||||||
int32_t len = ros::serialization::serializationLength(in);
|
|
||||||
ASSERT_EQ(len, 12); // 12 = 4 bytes for each item + 4-byte array length
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(Serialization, fixedSizeNonSimple_array)
|
|
||||||
{
|
|
||||||
boost::array<FixedSizeNonSimple, 2> in;
|
|
||||||
in[1].length_to_report = 100;
|
|
||||||
|
|
||||||
int32_t len = ros::serialization::serializationLength(in);
|
|
||||||
ASSERT_EQ(len, 8); // 8 = 4 bytes for each item
|
|
||||||
}
|
|
||||||
|
|
||||||
// Class used to make sure variable-size structs query the length of the every element
|
|
||||||
// in an array.
|
|
||||||
struct VariableSize
|
|
||||||
{
|
|
||||||
VariableSize()
|
|
||||||
: length_to_report(4)
|
|
||||||
{}
|
|
||||||
|
|
||||||
int32_t length_to_report;
|
|
||||||
};
|
|
||||||
|
|
||||||
namespace ros
|
|
||||||
{
|
|
||||||
namespace serialization
|
|
||||||
{
|
|
||||||
template<>
|
|
||||||
struct Serializer<VariableSize>
|
|
||||||
{
|
|
||||||
inline static uint32_t serializedLength(const VariableSize& v)
|
|
||||||
{
|
|
||||||
return v.length_to_report;
|
|
||||||
}
|
|
||||||
};
|
|
||||||
} // namespace serialization
|
|
||||||
} // namespace ros
|
|
||||||
|
|
||||||
TEST(Serialization, variableSize_vector)
|
|
||||||
{
|
|
||||||
std::vector<VariableSize> in;
|
|
||||||
in.resize(2);
|
|
||||||
in[1].length_to_report = 100;
|
|
||||||
|
|
||||||
int32_t len = ros::serialization::serializationLength(in);
|
|
||||||
ASSERT_EQ(len, 108); // 108 = 4 bytes for the first item + 100 bytes for the second + 4-byte array length
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(Serialization, variableSize_array)
|
|
||||||
{
|
|
||||||
boost::array<VariableSize, 2> in;
|
|
||||||
in[1].length_to_report = 100;
|
|
||||||
|
|
||||||
int32_t len = ros::serialization::serializationLength(in);
|
|
||||||
ASSERT_EQ(len, 104); // 104 = 4 bytes for the first item + 100 bytes for the second
|
|
||||||
}
|
|
||||||
|
|
||||||
struct AllInOneSerializer
|
|
||||||
{
|
|
||||||
uint32_t a;
|
|
||||||
};
|
|
||||||
|
|
||||||
namespace ros
|
|
||||||
{
|
|
||||||
namespace serialization
|
|
||||||
{
|
|
||||||
template<>
|
|
||||||
struct Serializer<AllInOneSerializer>
|
|
||||||
{
|
|
||||||
template<typename Stream, typename T>
|
|
||||||
inline static void allInOne(Stream& stream, T t)
|
|
||||||
{
|
|
||||||
stream.next(t.a);
|
|
||||||
}
|
|
||||||
|
|
||||||
ROS_DECLARE_ALLINONE_SERIALIZER;
|
|
||||||
};
|
|
||||||
} // namespace serialization
|
|
||||||
} // namespace ros
|
|
||||||
|
|
||||||
TEST(Serialization, allInOne)
|
|
||||||
{
|
|
||||||
AllInOneSerializer in, out;
|
|
||||||
in.a = 5;
|
|
||||||
serializeAndDeserialize(in, out);
|
|
||||||
ASSERT_EQ(out.a, in.a);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Class with a header, used to ensure message_traits::header(m) returns the header
|
|
||||||
struct WithHeader
|
|
||||||
{
|
|
||||||
WithHeader()
|
|
||||||
{}
|
|
||||||
|
|
||||||
roslib::Header header;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Class without a header, used to ensure message_traits::header(m) return NULL
|
|
||||||
struct WithoutHeader
|
|
||||||
{
|
|
||||||
WithoutHeader()
|
|
||||||
{}
|
|
||||||
};
|
|
||||||
|
|
||||||
namespace ros
|
|
||||||
{
|
|
||||||
namespace message_traits
|
|
||||||
{
|
|
||||||
template<> struct HasHeader<WithHeader> : public TrueType {};
|
|
||||||
} // namespace message_traits
|
|
||||||
} // namespace ros
|
|
||||||
|
|
||||||
TEST(MessageTraits, headers)
|
|
||||||
{
|
|
||||||
WithHeader wh;
|
|
||||||
WithoutHeader woh;
|
|
||||||
const WithHeader cwh;
|
|
||||||
const WithoutHeader cwoh;
|
|
||||||
|
|
||||||
wh.header.seq = 100;
|
|
||||||
ASSERT_TRUE(ros::message_traits::header(wh) != 0);
|
|
||||||
ASSERT_EQ(ros::message_traits::header(wh)->seq, 100UL);
|
|
||||||
|
|
||||||
ASSERT_TRUE(ros::message_traits::header(woh) == 0);
|
|
||||||
|
|
||||||
ASSERT_TRUE(ros::message_traits::header(cwh) != 0);
|
|
||||||
ASSERT_TRUE(ros::message_traits::header(cwoh) == 0);
|
|
||||||
|
|
||||||
ASSERT_TRUE(ros::message_traits::frameId(wh) != 0);
|
|
||||||
ASSERT_TRUE(ros::message_traits::frameId(woh) == 0);
|
|
||||||
ASSERT_TRUE(ros::message_traits::frameId(cwh) != 0);
|
|
||||||
ASSERT_TRUE(ros::message_traits::frameId(cwoh) == 0);
|
|
||||||
|
|
||||||
ASSERT_TRUE(ros::message_traits::timeStamp(wh) != 0);
|
|
||||||
ASSERT_TRUE(ros::message_traits::timeStamp(woh) == 0);
|
|
||||||
ASSERT_TRUE(ros::message_traits::timeStamp(cwh) != 0);
|
|
||||||
ASSERT_TRUE(ros::message_traits::timeStamp(cwoh) == 0);
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(Serialization, bufferOverrun)
|
|
||||||
{
|
|
||||||
Array b(new uint8_t[4]);
|
|
||||||
IStream stream(b.get(), 4);
|
|
||||||
uint32_t i;
|
|
||||||
deserialize(stream, i);
|
|
||||||
try
|
|
||||||
{
|
|
||||||
deserialize(stream, i);
|
|
||||||
FAIL();
|
|
||||||
}
|
|
||||||
catch(ros::Exception&)
|
|
||||||
{
|
|
||||||
SUCCEED();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(Serialization, streamOperators)
|
|
||||||
{
|
|
||||||
Array b(new uint8_t[4]);
|
|
||||||
OStream ostream(b.get(), 4);
|
|
||||||
uint32_t a = 5;
|
|
||||||
ostream << a;
|
|
||||||
a = 100;
|
|
||||||
IStream istream(b.get(), 4);
|
|
||||||
istream >> a;
|
|
||||||
ASSERT_EQ(a, 5UL);
|
|
||||||
}
|
|
||||||
|
|
||||||
int main(int argc, char** argv)
|
|
||||||
{
|
|
||||||
testing::InitGoogleTest(&argc, argv);
|
|
||||||
return RUN_ALL_TESTS();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -1,4 +0,0 @@
|
||||||
<launch>
|
|
||||||
<test test-name="builtin_types" pkg="test_roscpp_serialization" type="builtin_types"/>
|
|
||||||
</launch>
|
|
||||||
|
|
|
@ -1,5 +0,0 @@
|
||||||
<launch>
|
|
||||||
<test test-name="pre_deserialize" pkg="test_roscpp_serialization" type="pre_deserialize"/>
|
|
||||||
</launch>
|
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue