float64_test.cpp
Go to the documentation of this file.
00001 #include "ros_lib/ros/msg.h"
00002 #include <gtest/gtest.h>
00003 
00004 
00005 class TestFloat64 : public ::testing::Test
00006 {
00007 public:
00008   union
00009   {
00010     double val;
00011     unsigned char buffer[8];
00012   };
00013   
00014   static const double cases[];
00015   static const int num_cases;
00016 };
00017  
00018 const double TestFloat64::cases[] = {
00019   0.0, 10.0, 15642.1, -50.2, 0.0001, -0.321,
00020   123456.789, -987.654321, 3.4e38, -3.4e38,
00021 };
00022 const int TestFloat64::num_cases = sizeof(TestFloat64::cases) / sizeof(double);
00023 
00024 
00025 TEST_F(TestFloat64, testRoundTrip)
00026 {
00027   for (int i = 0; i < num_cases; i++)
00028   {
00029     memset(buffer, 0, sizeof(buffer));
00030     ros::Msg::serializeAvrFloat64(buffer, cases[i]);
00031     EXPECT_FLOAT_EQ(cases[i], val);
00032     
00033     float ret = 0;
00034     ros::Msg::deserializeAvrFloat64(buffer, &ret);
00035     EXPECT_FLOAT_EQ(cases[i], ret);
00036   }
00037 }
00038 
00039 
00040 int main(int argc, char **argv){
00041   testing::InitGoogleTest(&argc, argv);
00042   return RUN_ALL_TESTS();
00043 }


rosserial_client
Author(s): Michael Ferguson, Adam Stambler
autogenerated on Thu Jun 6 2019 19:56:25