ros-industrial / noether

Tool path planning and surface segmenter
124 stars 45 forks source link

Unable to generate half edge for simple example #150

Open rr-tom-noble opened 3 years ago

rr-tom-noble commented 3 years ago

Hi,

I'm trying to run the halfedge demo over a custom half-sphere mesh. Below is the output I'm receiving:

rob@aa-006:~/catkin_ws$ roslaunch noether_examples halfedge_edge_generator_demo.launch  mesh_file:=/home/rob/catkin_ws/src/noether/noether_examples/data/halfsphere.ply
... logging to /home/rob/.ros/log/32b999b4-ef8e-11eb-9bb1-870f19760e69/roslaunch-aa-006-34723.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://aa-006:42593/

SUMMARY
========

PARAMETERS
 * /halfedge_example_node/mesh_file: /home/rob/catkin_...
 * /rosdistro: noetic
 * /rosversion: 1.15.11

NODES
  /
    halfedge_example_node (noether_examples/halfedge_example_node)
    rviz (rviz/rviz)
    tool_path_planner_server (noether/tool_path_planner_server)

auto-starting new master
process[master]: started with pid [34731]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to 32b999b4-ef8e-11eb-9bb1-870f19760e69
process[rosout-1]: started with pid [34741]
started core service [/rosout]
process[halfedge_example_node-2]: started with pid [34744]
process[rviz-3]: started with pid [34749]
process[tool_path_planner_server-4]: started with pid [34750]
[ INFO] [1627467958.984518094]: Starting path generation
[ INFO] [1627467958.985661506]: Planning path
Error:   No valid edge segments were found, original mesh may have duplicate vertices
         at line 579 in /home/rob/catkin_ws/src/noether/tool_path_planner/src/halfedge_edge_generator.cpp
[ERROR] [1627467959.583676630]: Path planning on surface 1 failed
[ERROR] [1627467959.584935014]: Failed to generate edges from mesh
[halfedge_example_node-2] process has died [pid 34744, exit code 255, cmd /home/rob/catkin_ws/devel/lib/noether_examples/halfedge_example_node __name:=halfedge_example_node __log:=/home/rob/.ros/log/32b999b4-ef8e-11eb-9bb1-870f19760e69/halfedge_example_node-2.log].
log file: /home/rob/.ros/log/32b999b4-ef8e-11eb-9bb1-870f19760e69/halfedge_example_node-2*.log

The mesh in question can be found here: https://filebin.net/tkj0q0tni9oc0gpt

I'd much appreciate any help!

marip8 commented 3 years ago

Error: No valid edge segments were found, original mesh may have duplicate vertices at line 579 in /home/rob/catkin_ws/src/noether/tool_path_planner/src/halfedge_edge_generator.cpp

Can you verify that your mesh doesn't have duplicate vertices as the error suggests?

rr-tom-noble commented 3 years ago

Hey,

Can confirm that there are no duplicate vertices or faces

[ INFO] [1627486149.037619718] [/rviz_1627486141289212224]: Loading part from /home/rob/checkout/halfsphere.stl
[ INFO] [1627486149.070620718] [/rviz_1627486141289212224]: 8373 vertices found
[ INFO] [1627486149.070699354] [/rviz_1627486141289212224]: 16562 faces found
[ INFO] [1627486149.072684883] [/rviz_1627486141289212224]: Built cell locator
[ INFO] [1627486149.082425258] [/rviz_1627486141289212224]: Computed 16562 normals
[ INFO] [1627486157.490077649] [/rviz_1627486141289212224]: No duplicate vertices
[ INFO] [1627486159.996964390] [/rviz_1627486141289212224]: No duplicate faces

I used the following code to generate the mesh message / check for duplicates, where faces was, in this case, the list of all faces

shape_msgs::Mesh Mesh::toShapeMsgsMesh(std::vector<int> faces)
{
    std::map<int, int> vertex_id_mapping;
    shape_msgs::Mesh mesh;
    for (int i : faces)
    {
        shape_msgs::MeshTriangle triangle;
        vtkIdList* face = vtkIdList::New();
        mesh_->GetCellPoints(i, face);
        for (int j = 0; j < 3; j++)
        {
            int vertex_id = face->GetId(j);
            if (vertex_id_mapping.find(vertex_id) != vertex_id_mapping.end())
            {
                triangle.vertex_indices[j] = vertex_id_mapping[vertex_id];
                continue;
            }
            double* point = mesh_->GetPoint(vertex_id);
            geometry_msgs::Point vertex;
            vertex.x = point[0];
            vertex.y = point[1];
            vertex.z = point[2];
            mesh.vertices.push_back(vertex);
            vertex_id_mapping[vertex_id] = mesh.vertices.size() - 1;
            triangle.vertex_indices[j] = vertex_id_mapping[vertex_id];
        }
        mesh.triangles.push_back(triangle);
    }
    for (int i = 0; i < mesh.vertices.size(); i++)
    {
        for (int j = 0; j < mesh.vertices.size(); j++)
        {
            if (i == j)
                continue;
            geometry_msgs::Point p1 = mesh.vertices[i];
            geometry_msgs::Point p2 = mesh.vertices[j];
            if (p1.x == p2.x && p1.y == p2.y && p1.z == p2.z)
            {
                ROS_WARN("Mesh contains duplicate vertex!");
                return mesh;
            }
        }
    }
    ROS_INFO("No duplicate vertices");
    for (int i = 0; i < mesh.triangles.size(); i++)
    {
        for (int j = 0; j < mesh.triangles.size(); j++)
        {
            if (i == j)
                continue;
            auto f1 = mesh.triangles[i].vertex_indices;
            auto f2 = mesh.triangles[j].vertex_indices;
            if (f1[0] == f2[0] && f1[1] == f2[1] && f1[2] == f2[2])
            {
                ROS_WARN("Mesh contains duplicate face!");
                return mesh;
            }
        }
    }
    ROS_INFO("No duplicate faces");
    return mesh;
}

I'm also getting the same error when the list of faces passed is a subset (see #149) therefore I think the issues are one and the same

marip8 commented 3 years ago

if (p1.x == p2.x && p1.y == p2.y && p1.z == p2.z)

Comparing floats for equality is generally not a good idea because the last few decimal places of two floats that should be the same are usually slightly different. Instead you should check that the difference between the two floating point numbers is less than the machine epsilon:

if(abs(p1.x - p2.x) < std::numeric_limits<float>::epsilon() ... )

Give this change a try and share the result. I'm not sure you'll necessarily see anything different, but we can make sure we're doing the correct check. I looked at your meshes (half sphere and selection from #149), and they don't seem to have any visible issues.

I'm not sure this is the same issue as #149 because you've encountered two different issues with two different planners. The issue here is that the planner was not able to identify any edges in the mesh that was provided and therefore unable to generate a tool path. The issue in #149 is that it cannot find/generate vertex normals for the mesh that was provided in order to generate a tool path

DavidMerzJr commented 3 years ago

@marip8 asked me to take a look at this issue. I'll inspect the mesh to see if I can determine a direct answer to your problem. However, your code to check for duplicate faces is not quite correct, at least in terms of a half-edge mesh. In a half-edge mesh, an edge is a half-edge if there is only one triangle that connects two points. i.e. points A and B may each individually be part of several triangles, but there is only one triangle which contains both of them. If two (or more) triangles contain both A and B, then that is now a full edge.

    for (int i = 0; i < mesh.triangles.size(); i++)
    {
        for (int j = 0; j < mesh.triangles.size(); j++)
        {
            if (i == j)
                continue;
            auto f1 = mesh.triangles[i].vertex_indices;
            auto f2 = mesh.triangles[j].vertex_indices;
            if (f1[0] == f2[0] && f1[1] == f2[1] && f1[2] == f2[2])
            {
                ROS_WARN("Mesh contains duplicate face!");
                return mesh;
            }
        }
    }

This code checks for completely identical triangles (1-2-3 and 1-2-3), but fails to check for permutations (1-2-3 and 2-1-3). Since any two faces that both contain two vertices will prevent a half-edge from forming and being returned, you should check for all six permutations:

1-2-3, 2-3-1, 3-1-2, 3-2-1, 2-1-3, 1-3-2.

I will download and inspect your mesh.

rr-tom-noble commented 3 years ago

Thanks both. I'll make the changes to the duplicate checking code and let you know the results.

rr-tom-noble commented 3 years ago

Same results after making the above changes to the code

shape_msgs::Mesh Mesh::toShapeMsgsMesh(std::vector<int> faces)
{
    std::map<int, int> vertex_id_mapping;
    shape_msgs::Mesh mesh;
    for (int i : faces)
    {
        shape_msgs::MeshTriangle triangle;
        vtkIdList* face = vtkIdList::New();
        mesh_->GetCellPoints(i, face);
        for (int j = 0; j < 3; j++)
        {
            int vertex_id = face->GetId(j);
            if (vertex_id_mapping.find(vertex_id) != vertex_id_mapping.end())
            {
                triangle.vertex_indices[j] = vertex_id_mapping[vertex_id];
                continue;
            }
            double* point = mesh_->GetPoint(vertex_id);
            geometry_msgs::Point vertex;
            vertex.x = point[0];
            vertex.y = point[1];
            vertex.z = point[2];
            mesh.vertices.push_back(vertex);
            vertex_id_mapping[vertex_id] = mesh.vertices.size() - 1;
            triangle.vertex_indices[j] = vertex_id_mapping[vertex_id];
        }
        mesh.triangles.push_back(triangle);
    }
    for (int i = 0; i < mesh.vertices.size(); i++)
    {
        for (int j = 0; j < mesh.vertices.size(); j++)
        {
            if (i == j)
                continue;
            geometry_msgs::Point p1 = mesh.vertices[i];
            geometry_msgs::Point p2 = mesh.vertices[j];
            if (
                    abs(p1.x - p2.x) < std::numeric_limits<float>::epsilon() &&
                    abs(p1.y - p2.y) < std::numeric_limits<float>::epsilon() &&
                    abs(p1.z - p2.z) < std::numeric_limits<float>::epsilon()
                )
            {
                ROS_WARN("Mesh contains duplicate vertex!");
                return mesh;
            }
        }
    }
    ROS_INFO("No duplicate vertices");
    for (int i = 0; i < mesh.triangles.size(); i++)
    {
        for (int j = 0; j < mesh.triangles.size(); j++)
        {
            if (i == j)
                continue;
            auto f1 = mesh.triangles[i].vertex_indices;
            auto f2 = mesh.triangles[j].vertex_indices;
            if (
                    (f1[0] == f2[0] && f1[1] == f2[1] && f1[2] == f2[2]) ||
                    (f1[0] == f2[1] && f1[1] == f2[0] && f1[2] == f2[2]) ||
                    (f1[0] == f2[2] && f1[1] == f2[1] && f1[2] == f2[0]) ||
                    (f1[0] == f2[0] && f1[1] == f2[2] && f1[2] == f2[1]) ||
                    (f1[0] == f2[2] && f1[1] == f2[0] && f1[2] == f2[1]) ||
                    (f1[0] == f2[1] && f1[1] == f2[2] && f1[2] == f2[0])
                )
            {
                ROS_WARN("Mesh contains duplicate face!");
                return mesh;
            }
        }
    }
    ROS_INFO("No duplicate faces");
    return mesh;
}
[ INFO] [1627546118.703513464] [/rviz_1627546102223366828]: Loading part from /home/rob/checkout/halfsphere.stl
[ INFO] [1627546118.736922554] [/rviz_1627546102223366828]: 8373 vertices found
[ INFO] [1627546118.736978540] [/rviz_1627546102223366828]: 16562 faces found
[ INFO] [1627546118.738912113] [/rviz_1627546102223366828]: Built cell locator
[ INFO] [1627546118.746312482] [/rviz_1627546102223366828]: Computed 16562 normals
[ INFO] [1627546129.843597897] [/rviz_1627546102223366828]: No duplicate vertices
[ INFO] [1627546137.721620426] [/rviz_1627546102223366828]: No duplicate faces

@marip8 I still think #149 may be the same issue as, although the output warns about the normals, it still manages to generate the surface paths fine. It's when running the edge path generator afterwards (as that code uses both planners in sequence) that the code fails.

i.e.

[ INFO] [1627480014.856222657] [/toolpath_planner]: Handling toolpath plan request
[ INFO] [1627480014.857773656] [/toolpath_planner]: Loading mesh
[ INFO] [1627480014.857796108] [/toolpath_planner]: Loading mesh from service request
[ INFO] [1627480014.857847673] [/toolpath_planner]: Loading parameters
[ INFO] [1627480014.857946465] [/toolpath_planner]: Generating surface paths
[ INFO] [1627480014.858397418] [/tool_path_planner_server]: Starting path generation
[ INFO] [1627480014.858957040] [/tool_path_planner_server]: Planning path
... All of the warnings
[ INFO] [1627480014.889264177] [/tool_path_planner_server]: Surface 1 processed successfully
[ INFO] [1627480014.889615626] [/toolpath_planner]: Generating edge paths
[ INFO] [1627480014.889929894] [/tool_path_planner_server]: Starting path generation
[ INFO] [1627480014.889960505] [/tool_path_planner_server]: Planning path
Error:   No valid edge segments were found, original mesh may have duplicate vertices
         at line 579 in /home/rob/checkout/external/src/noether/tool_path_planner/src/halfedge_edge_generator.cpp
[ERROR] [1627480014.903492662] [/tool_path_planner_server]: Path planning on surface 1 failed
[ERROR] [1627480014.903696790] [/toolpath_planner]: Failed to generate edges from mesh
rr-tom-noble commented 3 years ago

@marip8 @DavidMerzJr

Hey both. Any progress with this? As a workaround I'm planning to implement a custom edge finder using straight lines between the ends of a plane slicer output, which should work fine for our use case. It'd be nice to have something more robust working though!

rr-tom-noble commented 3 years ago

@marip8 @DavidMerzJr Sorry to be a pain, but is still being looked into?

InigoMoreno commented 1 year ago

Something that helped me is changing the min_num_points on the config. If you run the halfedge demo, it will use the default values from the HalgEdgeGenerator::Config https://github.com/ros-industrial/noether/blob/e0b5b17c08e545bff471d9878ba43b3bd25ae27b/tool_path_planner/include/tool_path_planner/halfedge_edge_generator.h#L48-L69

You can change this by updating the code of the demo: Change theese lines) to

    noether_msgs::ToolPathConfig config_msg;
    config_msg.type = noether_msgs::ToolPathConfig::HALFEDGE_EDGE_GENERATOR;
    tool_path_planner::HalfedgeEdgeGenerator::Config config;
    config.min_num_points = 0;
    tool_path_planner::toHalfedgeConfigMsg(config_msg.halfedge_generator, config);

    goal.path_configs.push_back(config_msg);