Skip to content
Merged
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
34 changes: 24 additions & 10 deletions src/tool_path_planning_server.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#include <noether_ros/conversions.h>
#include <noether_ros/srv/plan_tool_path.hpp>

#include <filesystem>
#include <noether_tpp/core/tool_path_planner_pipeline.h>
#include <noether_tpp/utils.h>
#include <noether_tpp/plugin_interface.h>
Expand All @@ -25,25 +26,38 @@ class ToolPathPlanningServer : public rclcpp::Node
try
{
// Convert input configuration string/file to YAML node
YAML::Node config;
try
{
config = YAML::LoadFile(request->config);
}
catch (const YAML::Exception&)
// Load the configuration directly as a YAML-formatted string
YAML::Node config = YAML::Load(request->config);

// If the config is a scalar (and not a map), it's likely that the config is actually a file path and not a
// YAML-formatted string
if (config.IsScalar())
{
config = YAML::Load(request->config);
// Check if the configuration is an existing file
if (std::filesystem::is_regular_file(request->config) || std::filesystem::is_symlink(request->config))
{
// Reload the configuration from file
config = YAML::LoadFile(request->config);
}
else
{
throw std::runtime_error("The request TPP configuration looks like a file path but does not exist: '" +
request->config + "'");
}
}

// Check that the loaded request configuration is a map type
if (!config.IsMap())
throw std::runtime_error("The request TPP configuration must be a map type: '" + request->config + "'");

// Load the mesh file
pcl::PolygonMesh mesh;
if (pcl::io::loadPolygonFile(request->mesh_file, mesh) <= 0)
throw std::runtime_error("Failed to load mesh from file: " + request->mesh_file);

// Set the mesh frame from the request
mesh.header.frame_id = request->mesh_frame;

if (pcl::io::loadPolygonFile(request->mesh_file, mesh) <= 0)
throw std::runtime_error("Failed to load mesh from file: " + request->mesh_file);

// Create and run the tool path planning pipeline
noether::Factory factory;
noether::ToolPathPlannerPipeline pipeline(factory, config);
Expand Down
Loading