Skip to content

Commit

Permalink
update
Browse files Browse the repository at this point in the history
  • Loading branch information
markaren committed Jun 25, 2024
1 parent a08cb58 commit 25f61cb
Show file tree
Hide file tree
Showing 4 changed files with 71 additions and 45 deletions.
24 changes: 15 additions & 9 deletions examples/loaders/urdf_loader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,16 @@ using namespace threepp;

int main(int argc, char** argv) {

if (argc != 2) return 1;
if (argc != 2) {
std::cerr << "Usage: " << argv[0] << " <urdf file>" << std::endl;
return 1;
}

std::string urdfPath = argv[1];
std::filesystem::path urdfPath = argv[1];
if (!std::filesystem::exists(urdfPath)) {
std::cerr << "File not found: " << urdfPath << std::endl;
return 1;
}

Canvas canvas{"URDF loader", {{"aa", 4}}};
GLRenderer renderer(canvas.size());
Expand Down Expand Up @@ -38,7 +45,7 @@ int main(int argc, char** argv) {

Vector3 size;
bb.getSize(size);
camera->position.copy(size).multiplyScalar(1.5).setX(0);
camera->position.set(0, size.y * 1.5f, size.z * 3.f);
controls.update();

canvas.onWindowResize([&](WindowSize size) {
Expand All @@ -51,16 +58,15 @@ int main(int argc, char** argv) {
canvas.animate([&]() {
const auto dt = clock.getDelta();

model->getObjectByName("joint_1")->rotation.y += dt * 0.1;
model->getObjectByName("joint_2")->rotation.z += dt * 0.1;
model->getObjectByName("joint_3")->rotation.z += dt * 0.1;
model->getObjectByName("joint_4")->rotation.x += dt * 0.1;
model->getObjectByName("joint_1")->rotation.y += dt * 0.1f;
model->getObjectByName("joint_2")->rotation.z += dt * 0.1f;
model->getObjectByName("joint_3")->rotation.z += dt * 0.1f;
model->getObjectByName("joint_4")->rotation.x += dt * 0.1f;
// model->getObjectByName("joint_5")->rotation.y += dt * 0.1;
// model->getObjectByName("joint_6")->rotation.y += dt * 0.1;

model->updateMatrixWorld();

renderer.render(*scene, *camera);
});

}
}
20 changes: 20 additions & 0 deletions include/threepp/loaders/Loader.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@

#ifndef THREEPP_LOADER_HPP
#define THREEPP_LOADER_HPP

#include <filesystem>
#include <memory>

namespace threepp {

template<class T>
class Loader {
public:
virtual std::shared_ptr<T> load(const std::filesystem::path& path) = 0;

virtual ~Loader() = default;
};

}// namespace threepp

#endif//THREEPP_LOADER_HPP
14 changes: 4 additions & 10 deletions include/threepp/loaders/URDFLoader.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,21 +2,15 @@
#ifndef THREEPP_URDFLOADER_HPP
#define THREEPP_URDFLOADER_HPP

#include <memory>
#include "threepp/loaders/Loader.hpp"

#include <filesystem>
#include <memory>

namespace threepp {

class Group;

template <class T>
class Loader {
public:
virtual std::shared_ptr<T> load(const std::filesystem::path& path) = 0;

virtual ~Loader() = default;
};

class URDFLoader {

public:
Expand All @@ -31,6 +25,6 @@ namespace threepp {
std::unique_ptr<Impl> pimpl_;
};

}
}// namespace threepp

#endif//THREEPP_URDFLOADER_HPP
58 changes: 32 additions & 26 deletions src/threepp/loaders/URDFLoader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,32 @@ namespace {
-utils::parseFloat(xyz[2]));
}

std::filesystem::path getModelPath(const std::filesystem::path& basePath, std::string fileName) {

if (fileName.find("package://") != std::string::npos) {

fileName = fileName.substr(10);

//find parent path with package.xml
bool packageFound = false;
auto packagePath = basePath.parent_path();
for (int i = 0; i < 10; ++i) {
if (exists(packagePath / "package.xml")) {
packageFound = true;
break;
}
packagePath = packagePath.parent_path();
}
if (!packageFound) {
return "";
}

return packagePath.parent_path().string() + "/" + fileName;
}

return fileName;
}

}// namespace

struct URDFLoader::Impl {
Expand All @@ -50,7 +76,7 @@ struct URDFLoader::Impl {
object->name = root.attribute("name").as_string("robot");

std::vector<std::shared_ptr<Object3D>> links;
for (auto link : root.children("link")) {
for (const auto link : root.children("link")) {

auto linkObject = std::make_shared<Object3D>();
linkObject->name = link.attribute("name").value();
Expand All @@ -59,40 +85,20 @@ struct URDFLoader::Impl {
// object->add(linkObject);
// }

for (auto visual : link.children("visual")) {
for (const auto visual : link.children("visual")) {

auto visualObject = std::make_shared<Object3D>();
visualObject->name = visual.attribute("name").value();

visualObject->position.copy(getXYZ(visual));
visualObject->rotation.copy(getRPY(visual));

for (auto geometry : visual.children("geometry")) {
for (const auto geometry : visual.children("geometry")) {

auto mesh = geometry.child("mesh");
auto fileName = std::string(mesh.attribute("filename").value());

if (fileName.find("package://") == 0) {
fileName = fileName.substr(10);
//find parent path with package.xml
bool packageFound = false;
auto packagePath = path.parent_path();
for (int i = 0; i < 10; ++i) {
if (exists(packagePath / "package.xml")) {
packageFound = true;
break;
}
packagePath = packagePath.parent_path();
}
if (!packageFound) {
return nullptr;
}

fileName = packagePath.parent_path().string() + "/" + fileName;
}
auto fileName = getModelPath(path, mesh.attribute("filename").value());

auto load = loader.load(fileName);
if (load) {
if (auto load = loader.load(fileName)) {
visualObject->add(load);
}
}
Expand All @@ -116,7 +122,7 @@ struct URDFLoader::Impl {
links.emplace_back(linkObject);
}

for (auto joint : root.children("joint")) {
for (const auto joint : root.children("joint")) {

auto jointObject = std::make_shared<Object3D>();
jointObject->name = joint.attribute("name").value();
Expand Down

0 comments on commit 25f61cb

Please sign in to comment.