예제 #1
0
TEST(Matrices,SerializeCMatrixD)
{
	CMatrixDouble	A(3,2, dat_A);
	CMatrixFixedNumeric<double,3,2>	fA;

	CMatrixD	As = A;

	CMemoryStream	membuf;
	membuf << As;
	membuf.Seek(0);
	membuf >> fA;

	EXPECT_NEAR(0,fabs((CMatrixDouble(fA) - A).sum()), 1e-9);

	try
	{
		// Now, if we try to de-serialize into the wrong type, we should get an exception:
		membuf.Seek(0);
		CMatrixFixedNumeric<double,2,2>	fB;
		membuf >> fB;  // Wrong size!

		GTEST_FAIL() << "Exception not launched when it was expected!";
	}
	catch(...)
	{ // OK, exception occurred, as expected
	}
}
예제 #2
0
// Serialize and deserialize complex STL types
TEST(SerializeTestBase, STL_serialization)
{
	try
	{
		// std::vector<>
		{
			CMemoryStream  buf;

			std::vector<double> a,b;
			a.resize(30);
			for (size_t i=0;i<a.size();i++) a[i]=50-i;

			buf << a; buf.Seek(0); buf >> b;
			EXPECT_TRUE(a==b);
		}

		// std::list<...>
		{
			CMemoryStream  buf;

			std::list<std::map<double,std::set<std::string> > >  a,b;

			// Fill with random:
			mrpt::random::CRandomGenerator rng;
			const size_t N = rng.drawUniform(10,30);
			for (size_t i=0;i<N;i++)
			{
				std::map<double,std::set<std::string> > d;
				const size_t M = rng.drawUniform(4,9);
				for (size_t j=0;j<M;j++)
				{
					std::set<std::string> & dd = d[ rng.drawGaussian1D_normalized() ];
					const size_t L = rng.drawUniform(2,15);
					for (size_t k=0;k<L;k++)
						dd.insert(mrpt::format("%f", rng.drawGaussian1D_normalized() ));
				}
				a.push_back(d);
			}


			buf << a; buf.Seek(0); buf >> b;
			EXPECT_TRUE(a==b);
		}
	}
	catch(std::exception &e)
	{
		GTEST_FAIL() <<
			"Exception:\n" << e.what() << endl;
	}

}
예제 #3
0
// Create a set of classes, then serialize and deserialize to test possible
// bugs:
TEST(SerializeTestOpenGL, WriteReadToMem)
{
	const mrpt::utils::TRuntimeClassId* lstClasses[] = {
		CLASS_ID(CAxis),
		CLASS_ID(CBox),
		CLASS_ID(CFrustum),
		CLASS_ID(CDisk),
		CLASS_ID(CGridPlaneXY),
#if MRPT_HAS_OPENCV  // These classes need CImage serialization
		CLASS_ID(CMesh),
		CLASS_ID(CTexturedPlane),
#endif
		CLASS_ID(COpenGLViewport),
		CLASS_ID(CPointCloud),
		CLASS_ID(CPointCloudColoured),
		CLASS_ID(CSetOfLines),
		CLASS_ID(CSetOfTriangles),
		CLASS_ID(CSphere),
		CLASS_ID(CCylinder),
		CLASS_ID(CGeneralizedCylinder),
		CLASS_ID(CPolyhedron),
		CLASS_ID(CArrow),
		CLASS_ID(CCamera),
		CLASS_ID(CEllipsoid),
		CLASS_ID(CGridPlaneXZ),
		CLASS_ID(COpenGLScene),
		CLASS_ID(CSetOfObjects),
		CLASS_ID(CSimpleLine),
		CLASS_ID(CText),
		CLASS_ID(CText3D),
		CLASS_ID(CEllipsoidInverseDepth2D),
		CLASS_ID(CEllipsoidInverseDepth3D),
		CLASS_ID(CEllipsoidRangeBearing2D),
		CLASS_ID(COctoMapVoxels)
	};

	for (size_t i = 0; i < sizeof(lstClasses) / sizeof(lstClasses[0]); i++)
	{
		try
		{
			CMemoryStream buf;
			{
				CSerializable* o =
					static_cast<CSerializable*>(lstClasses[i]->createObject());
				buf << *o;
				delete o;
			}

			CSerializable::Ptr recons;
			buf.Seek(0);
			buf >> recons;
		}
		catch (std::exception& e)
		{
			GTEST_FAIL() << "Exception during serialization test for class '"
						 << lstClasses[i]->className << "':\n"
						 << e.what() << endl;
		}
	}
}
예제 #4
0
// IStream members
STDMETHODIMP CMemoryStream::Clone(IStream **ppstm)
{
    TraceEnter();
    if (NULL == ppstm)
    {
        return E_INVALIDARG;
    }

    CMemoryStream *pMemoryStream = new CMemoryStream(m_pbBuffer, m_nSize);

    if (NULL == pMemoryStream)
    {
        return E_INVALIDARG;
    }
    
    LARGE_INTEGER dlibMove;
    dlibMove.QuadPart = m_nPos;
    DWORD dwOrigin = STREAM_SEEK_SET;
    ULARGE_INTEGER dlibNewPosition;

    HRESULT hr = pMemoryStream->Seek(dlibMove, dwOrigin, &dlibNewPosition);

    if (FAILED(hr))
    {
        pMemoryStream->Release();
        return hr;
    }
    else
    {
        *ppstm = (IStream *)pMemoryStream;
        return S_OK;
    }
}
예제 #5
0
// Create a set of classes, then serialize and deserialize to test possible
// bugs:
TEST(NavTests, Serialization_WriteReadToMem)
{
	for (size_t i = 0; i < sizeof(lstClasses) / sizeof(lstClasses[0]); i++)
	{
		try
		{
			CMemoryStream buf;
			{
				CSerializable* o =
					static_cast<CSerializable*>(lstClasses[i]->createObject());
				buf << *o;
				delete o;
			}

			CSerializable::Ptr recons;
			buf.Seek(0);
			buf >> recons;
		}
		catch (std::exception& e)
		{
			GTEST_FAIL() << "Exception during serialization test for class '"
						 << lstClasses[i]->className << "':\n"
						 << e.what() << endl;
		}
	}
}
예제 #6
0
파일: File.cpp 프로젝트: nightstyles/focp
int32 CFile::Write(CMemoryStream& oStream, int32 nWriteSize)
{
	if(nWriteSize <= 0)
		return 0;
	uint32 nRest = oStream.GetSize() - oStream.GetPosition();
	if(nRest < (uint32)nWriteSize)
		nWriteSize = nRest;
	int32 nRet, nOldCopySize = nWriteSize;
	while(nWriteSize)
	{
		uint32 nBlockSize;
		char* pBuf = oStream.GetBuf(nBlockSize);
		if(nBlockSize > (uint32)nWriteSize)
			nBlockSize = nWriteSize;
		nRet = Write(pBuf, nBlockSize);
		if(nRet < 0)
		{
			if(nWriteSize == nOldCopySize)
				return nRet;
			break;
		}
		if(nRet == 0)
			break;
		nWriteSize -= nRet;
		oStream.Seek(nRet);
	}
	return nOldCopySize - nWriteSize;
}
예제 #7
0
/* -----------------------------------------------------------------------
	Used to pass CORBA-like object into a MRPT object.
		See doc about "Integration with BABEL".
   ----------------------------------------------------------------------- */
void utils::StringToObject(const std::string &str, CSerializablePtr &obj)
{
	MRPT_START

	obj.clear_unique();
	if (str.empty()) return;

	CMemoryStream	tmp;
	size_t			n;
	size_t			i,lastIdx;

	obj.clear_unique();

	n = str.size();

	// Scan the string to decode it:
	// ----------------------------------
	lastIdx = 0;
	const char *data = str.c_str();
	unsigned char c;
	for (i=0;i<n && (c=data[i])!=0;i++)
	{
		// Search for first "0x01" byte:
		if ( c == 0x01 )
		{
			// Copy all till now:
			tmp.WriteBuffer( &data[lastIdx], i - lastIdx + 1 );
			i+=1; // +1 from "for" loop
			lastIdx = i+1;

			// And decode:
			//   0x01 0x01 --> 0x01
			//   0x01 0x02 --> 0x00
			if (data[i]==0x01)
					((unsigned char*)tmp.getRawBufferData())[tmp.getTotalBytesCount()-1] = (unsigned char)0x01;
			else 	((unsigned char*)tmp.getRawBufferData())[tmp.getTotalBytesCount()-1] = (unsigned char)0x00;
		}
	} // end for i

	// Copy the rest:
	if ( (n-lastIdx) > 0)
		tmp.WriteBuffer( &data[lastIdx], n - lastIdx );

	// And the '\0' char:
	char dummy = '\0';
	tmp.WriteBuffer( &dummy, sizeof(char) );

	tmp.Seek(0,CStream::sFromBeginning);
	obj = tmp.ReadObject();

	MRPT_END

}
예제 #8
0
// Create a set of classes, then serialize and deserialize to test possible bugs:
TEST(SerializeTestObs, WriteReadToMem)
{
	const mrpt::utils::TRuntimeClassId* lstClasses[] = {
		// Observations:
		CLASS_ID(CObservation2DRangeScan),
		CLASS_ID(CObservation3DRangeScan),
		CLASS_ID(CObservationBearingRange),
		CLASS_ID(CObservationBatteryState),
		CLASS_ID(CObservationWirelessPower),
		CLASS_ID(CObservationRFID),
		CLASS_ID(CObservationBeaconRanges),
		CLASS_ID(CObservationComment),
		CLASS_ID(CObservationGasSensors),
		CLASS_ID(CObservationGPS),
		CLASS_ID(CObservationImage),
		CLASS_ID(CObservationReflectivity),
		CLASS_ID(CObservationIMU),
		CLASS_ID(CObservationOdometry),
		CLASS_ID(CObservationRange),
		CLASS_ID(CObservationStereoImages),
		CLASS_ID(CObservationCANBusJ1939),
		CLASS_ID(CObservationRawDAQ),
		// Actions:
		CLASS_ID(CActionRobotMovement2D),
		CLASS_ID(CActionRobotMovement3D)
		};

	for (size_t i=0;i<sizeof(lstClasses)/sizeof(lstClasses[0]);i++)
	{
		try
		{
			CMemoryStream  buf;
			{
				CSerializable* o = static_cast<CSerializable*>(lstClasses[i]->createObject());
				buf << *o;
				delete o;
			}

			CSerializablePtr recons;
			buf.Seek(0);
			buf >> recons;
		}
		catch(std::exception &e)
		{
			GTEST_FAIL() <<
				"Exception during serialization test for class '"<< lstClasses[i]->className <<"':\n" << e.what() << endl;
		}
	}
}
예제 #9
0
파일: File.cpp 프로젝트: nightstyles/focp
int32 CFile::Read(CMemoryStream& oStream, int32 nReadSize, uint32 nTimeOut)
{
	if(nReadSize <= 0)
		return 0;
	if(oStream.GetSize() == oStream.GetPosition())
	{
		if(!oStream.ExtendSize(nReadSize))
			return 0;
	}
	uint32 nBlockSize;
	char* pBuf = oStream.GetBuf(nBlockSize);
	if(nBlockSize > (uint32)nReadSize)
		nBlockSize = nReadSize;
	int32 nRet = Read(pBuf, nBlockSize, nTimeOut);//???????
	if(nRet > 0)
		oStream.Seek(nRet);
	return nRet;
}
예제 #10
0
// Create a set of classes, then serialize and deserialize to test possible
// bugs:
TEST(SerializeTestMaps, WriteReadToMem)
{
	const mrpt::utils::TRuntimeClassId* lstClasses[] = {
		CLASS_ID(CBeacon),
		CLASS_ID(CBeaconMap),
		CLASS_ID(CColouredPointsMap),
		CLASS_ID(CGasConcentrationGridMap2D),
		CLASS_ID(CWirelessPowerGridMap2D),
		CLASS_ID(CHeightGridMap2D),
		CLASS_ID(CReflectivityGridMap2D),
		CLASS_ID(COccupancyGridMap2D),
		CLASS_ID(CSimplePointsMap),
		CLASS_ID(CRandomFieldGridMap3D),
		CLASS_ID(CWeightedPointsMap),
		CLASS_ID(COctoMap),
		CLASS_ID(CColouredOctoMap)};

	for (size_t i = 0; i < sizeof(lstClasses) / sizeof(lstClasses[0]); i++)
	{
		try
		{
			CMemoryStream buf;
			{
				CSerializable* o =
					static_cast<CSerializable*>(lstClasses[i]->createObject());
				buf << *o;
				delete o;
			}

			CSerializable::Ptr recons;
			buf.Seek(0);
			buf >> recons;
		}
		catch (std::exception& e)
		{
			GTEST_FAIL() << "Exception during serialization test for class '"
						 << lstClasses[i]->className << "':\n"
						 << e.what() << endl;
		}
	}
}
예제 #11
0
// Create a set of classes, then serialize and deserialize to test possible bugs:
TEST(SerializeTestBase, CArray)
{
	try
	{
		CMemoryStream  buf;
		CArrayDouble<5>  a, b;
		for (CArrayDouble<5>::Index i=0;i<a.size();i++) a[i] = i+10;

		buf << a;
		buf.Seek(0);
		buf >> b;

		EXPECT_TRUE(a==b);
	}
	catch(std::exception &e)
	{
		GTEST_FAIL() <<
			"Exception:\n" << e.what() << endl;
	}

}
예제 #12
0
// Create a set of classes, then serialize and deserialize to test possible bugs:
TEST(SerializeTestBase, WriteReadToMem)
{
	const mrpt::utils::TRuntimeClassId* lstClasses[] = {
		// Misc:
		CLASS_ID(CPose2D),
		CLASS_ID(CPose3D),
		CLASS_ID(CPose3DQuat),
		CLASS_ID(CPoint2D),
		CLASS_ID(CPoint3D),
		// Poses:
		CLASS_ID(CPose3DPDFGaussian),
		CLASS_ID(CPose3DQuatPDFGaussian)
		};

	for (size_t i=0;i<sizeof(lstClasses)/sizeof(lstClasses[0]);i++)
	{
		try
		{
			CMemoryStream  buf;
			{
				CSerializable* o = static_cast<CSerializable*>(lstClasses[i]->createObject());
				buf << *o;
				delete o;
			}

			CSerializablePtr recons;
			buf.Seek(0);
			buf >> recons;
		}
		catch(std::exception &e)
		{
			GTEST_FAIL() <<
				"Exception during serialization test for class '"<< lstClasses[i]->className <<"':\n" << e.what() << endl;
		}
	}
}