Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add unit tests to cover new addTrajectoryLinkCommand #881

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions tesseract_common/include/tesseract_common/resource_locator.h
Original file line number Diff line number Diff line change
Expand Up @@ -92,6 +92,8 @@ class GeneralResourceLocator : public ResourceLocator
void serialize(Archive& ar, const unsigned int version); // NOLINT

std::unordered_map<std::string, std::string> package_paths_;

void processToken(const std::string& token);
};

/** @brief Represents resource data available from a file or url */
Expand Down
6 changes: 5 additions & 1 deletion tesseract_common/src/joint_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,8 @@ bool JointTrajectory::operator==(const JointTrajectory& other) const

bool JointTrajectory::operator!=(const JointTrajectory& rhs) const { return !operator==(rhs); }

// LCOV_EXCL_START

///////////////
// Iterators //
///////////////
Expand Down Expand Up @@ -121,7 +123,7 @@ JointTrajectory::const_reference JointTrajectory::at(size_type n) const { return
JointTrajectory::pointer JointTrajectory::data() { return states.data(); }
JointTrajectory::const_pointer JointTrajectory::data() const { return states.data(); }
JointTrajectory::reference JointTrajectory::operator[](size_type pos) { return states[pos]; }
JointTrajectory::const_reference JointTrajectory::operator[](size_type pos) const { return states[pos]; };
JointTrajectory::const_reference JointTrajectory::operator[](size_type pos) const { return states[pos]; }

///////////////
// Modifiers //
Expand Down Expand Up @@ -164,6 +166,8 @@ void JointTrajectory::emplace_back(Args&&... args)
void JointTrajectory::pop_back() { states.pop_back(); }
void JointTrajectory::swap(std::vector<value_type>& other) { states.swap(other); }

// LCOV_EXCL_STOP

template <class Archive>
void JointTrajectory::serialize(Archive& ar, const unsigned int version) // NOLINT
{
Expand Down
57 changes: 36 additions & 21 deletions tesseract_common/src/resource_locator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,19 +66,7 @@ GeneralResourceLocator::GeneralResourceLocator()
boost::split(tokens, tesseract_resource_paths, boost::is_any_of(";"), boost::token_compress_on);
#endif
for (const auto& token : tokens)
{
tesseract_common::fs::path d(token);
if (tesseract_common::fs::is_directory(d) && tesseract_common::fs::exists(d))
{
std::string dir_name = d.filename().string();
if (package_paths_.find(dir_name) == package_paths_.end())
package_paths_[dir_name] = token;
}
else
{
CONSOLE_BRIDGE_logWarn("Package Path does not exist: %s", token.c_str());
}
}
processToken(token);
}

char* ros_package_paths = std::getenv("ROS_PACKAGE_PATH");
Expand All @@ -91,20 +79,47 @@ GeneralResourceLocator::GeneralResourceLocator()
boost::split(tokens, ros_package_paths, boost::is_any_of(";"), boost::token_compress_on);
#endif
for (const auto& token : tokens)
processToken(token);
}
}

void GeneralResourceLocator::processToken(const std::string& token)
{
tesseract_common::fs::path d(token);
if (tesseract_common::fs::is_directory(d) && tesseract_common::fs::exists(d))
{
// Check current directory
tesseract_common::fs::path check = d;
check.append("package.xml");
if (tesseract_common::fs::exists(check))
{
tesseract_common::fs::path d(token);
if (tesseract_common::fs::is_directory(d) && tesseract_common::fs::exists(d))
std::string dir_name = d.filename().string();
if (package_paths_.find(dir_name) == package_paths_.end())
package_paths_[dir_name] = d.string();
}

// Check all subdirectories
tesseract_common::fs::recursive_directory_iterator dir(d), end;
while (dir != end)
{
tesseract_common::fs::path check = dir->path();
check.append("package.xml");
if (tesseract_common::fs::exists(check))
{
std::string dir_name = d.filename().string();
std::string dir_name = dir->path().filename().string();
if (package_paths_.find(dir_name) == package_paths_.end())
package_paths_[dir_name] = token;
}
else
{
CONSOLE_BRIDGE_logError("Package Path does not exist: &s", token.c_str());
package_paths_[dir_name] = dir->path().string();

dir.no_push(); // don't recurse into this directory.
}

++dir;
}
}
else
{
CONSOLE_BRIDGE_logError("Package Path does not exist: &s", token.c_str());
}
}

std::shared_ptr<Resource> GeneralResourceLocator::locateResource(const std::string& url) const
Expand Down
234 changes: 234 additions & 0 deletions tesseract_common/test/tesseract_common_serialization_unit.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -330,6 +330,240 @@ TEST(TesseractCommonSerializeUnit, VectorXd) // NOLINT
}
}

TEST(TesseractCommonSerializeUnit, VectorXi) // NOLINT
{
{ // Serialize empty object
Eigen::VectorXi ev;
{
std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_xi_boost.xml");
boost::archive::xml_oarchive oa(os);
oa << BOOST_SERIALIZATION_NVP(ev);
}

Eigen::VectorXi nev;
{
std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_xi_boost.xml");
assert(ifs.good());
boost::archive::xml_iarchive ia(ifs);

// restore the schedule from the archive
ia >> BOOST_SERIALIZATION_NVP(nev);
}
}

// Serialize to object which already has data
for (int i = 0; i < 5; ++i)
{
Eigen::VectorXi ev = Eigen::VectorXi::Random(6);

{
std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_xi_boost.xml");
boost::archive::xml_oarchive oa(os);
oa << BOOST_SERIALIZATION_NVP(ev);
}

Eigen::VectorXi nev = Eigen::VectorXi::Random(6);
{
std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_xi_boost.xml");
assert(ifs.good());
boost::archive::xml_iarchive ia(ifs);

// restore the schedule from the archive
ia >> BOOST_SERIALIZATION_NVP(nev);
}

EXPECT_TRUE(ev == nev);
}

// Serialize to object which already has data and different size
for (int i = 0; i < 5; ++i)
{
Eigen::VectorXi ev = Eigen::VectorXi::Random(6);

{
std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_xi_boost.xml");
boost::archive::xml_oarchive oa(os);
oa << BOOST_SERIALIZATION_NVP(ev);
}

Eigen::VectorXi nev = Eigen::VectorXi::Random(3);
{
std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_xi_boost.xml");
assert(ifs.good());
boost::archive::xml_iarchive ia(ifs);

// restore the schedule from the archive
ia >> BOOST_SERIALIZATION_NVP(nev);
}

EXPECT_TRUE(ev == nev);
}

// Default use case
for (int i = 0; i < 5; ++i)
{
Eigen::VectorXi ev = Eigen::VectorXi::Random(6);

{
std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_xi_boost.xml");
boost::archive::xml_oarchive oa(os);
oa << BOOST_SERIALIZATION_NVP(ev);
}

Eigen::VectorXi nev;
{
std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_xi_boost.xml");
assert(ifs.good());
boost::archive::xml_iarchive ia(ifs);

// restore the schedule from the archive
ia >> BOOST_SERIALIZATION_NVP(nev);
}

EXPECT_TRUE(ev == nev);
}
}

TEST(TesseractCommonSerializeUnit, Vector3d) // NOLINT
{
{ // Serialize empty object
Eigen::Vector3d ev;
{
std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_3d_boost.xml");
boost::archive::xml_oarchive oa(os);
oa << BOOST_SERIALIZATION_NVP(ev);
}

Eigen::Vector3d nev;
{
std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_3d_boost.xml");
assert(ifs.good());
boost::archive::xml_iarchive ia(ifs);

// restore the schedule from the archive
ia >> BOOST_SERIALIZATION_NVP(nev);
}
}

// Serialize to object which already has data
for (int i = 0; i < 3; ++i)
{
Eigen::Vector3d ev = Eigen::Vector3d::Random();

{
std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_3d_boost.xml");
boost::archive::xml_oarchive oa(os);
oa << BOOST_SERIALIZATION_NVP(ev);
}

Eigen::Vector3d nev = Eigen::Vector3d::Random();
{
std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_3d_boost.xml");
assert(ifs.good());
boost::archive::xml_iarchive ia(ifs);

// restore the schedule from the archive
ia >> BOOST_SERIALIZATION_NVP(nev);
}

EXPECT_TRUE(ev.isApprox(nev, 1e-5));
}

// Default use case
for (int i = 0; i < 3; ++i)
{
Eigen::Vector3d ev = Eigen::Vector3d::Random();

{
std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_3d_boost.xml");
boost::archive::xml_oarchive oa(os);
oa << BOOST_SERIALIZATION_NVP(ev);
}

Eigen::Vector3d nev;
{
std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_3d_boost.xml");
assert(ifs.good());
boost::archive::xml_iarchive ia(ifs);

// restore the schedule from the archive
ia >> BOOST_SERIALIZATION_NVP(nev);
}

EXPECT_TRUE(ev.isApprox(nev, 1e-5));
}
}

TEST(TesseractCommonSerializeUnit, Vector4d) // NOLINT
{
{ // Serialize empty object
Eigen::Vector4d ev;
{
std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_4d_boost.xml");
boost::archive::xml_oarchive oa(os);
oa << BOOST_SERIALIZATION_NVP(ev);
}

Eigen::Vector4d nev;
{
std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_4d_boost.xml");
assert(ifs.good());
boost::archive::xml_iarchive ia(ifs);

// restore the schedule from the archive
ia >> BOOST_SERIALIZATION_NVP(nev);
}
}

// Serialize to object which already has data
for (int i = 0; i < 4; ++i)
{
Eigen::Vector4d ev = Eigen::Vector4d::Random();

{
std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_4d_boost.xml");
boost::archive::xml_oarchive oa(os);
oa << BOOST_SERIALIZATION_NVP(ev);
}

Eigen::Vector4d nev = Eigen::Vector4d::Random();
{
std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_4d_boost.xml");
assert(ifs.good());
boost::archive::xml_iarchive ia(ifs);

// restore the schedule from the archive
ia >> BOOST_SERIALIZATION_NVP(nev);
}

EXPECT_TRUE(ev.isApprox(nev, 1e-5));
}

// Default use case
for (int i = 0; i < 4; ++i)
{
Eigen::Vector4d ev = Eigen::Vector4d::Random();

{
std::ofstream os(tesseract_common::getTempPath() + "eigen_vector_4d_boost.xml");
boost::archive::xml_oarchive oa(os);
oa << BOOST_SERIALIZATION_NVP(ev);
}

Eigen::Vector4d nev;
{
std::ifstream ifs(tesseract_common::getTempPath() + "eigen_vector_4d_boost.xml");
assert(ifs.good());
boost::archive::xml_iarchive ia(ifs);

// restore the schedule from the archive
ia >> BOOST_SERIALIZATION_NVP(nev);
}

EXPECT_TRUE(ev.isApprox(nev, 1e-5));
}
}

TEST(TesseractCommonSerializeUnit, MatrixX2d) // NOLINT
{
{ // Serialize empty
Expand Down
Loading