Skip to content

Commit f250219

Browse files
authored
Merge pull request #121 from marip8/fix/raster_wrt_global_axes
Raster w.r.t. a specified direction
2 parents e77d0d5 + 8302955 commit f250219

File tree

5 files changed

+27
-32
lines changed

5 files changed

+27
-32
lines changed

noether_msgs/msg/SurfaceWalkRasterGeneratorConfig.msg

Lines changed: 1 addition & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -5,13 +5,5 @@ float64 intersection_plane_height # Used by the raster_tool_path_planner when o
55
float64 min_hole_size # A path may pass over holes smaller than this, but must be broken when larger holes are encounterd.
66
float64 min_segment_size # The minimum segment size to allow when finding intersections; small segments will be discarded
77
float64 raster_rot_offset # Specifies the direction of the raster path in radians
8-
9-
# When set to TRUE: initial cuts are determined using the axes of the
10-
# coordinate frame in which the mesh is placed. This may cause the
11-
# initial cut to miss the part.
12-
# When set to FALSE: initial cuts are determined using the centroid and
13-
# principal axes of the part. This is the old default behavior. (Note
14-
# that ROS sets message fields to 0/False by default.)
15-
bool raster_wrt_global_axes
16-
178
bool generate_extra_rasters # Whether an extra raster stroke should be added to the beginning and end of the raster pattern
9+
geometry_msgs/Vector3 cut_direction # Desired raster direction, in mesh coordinate system (i.e. global coordinate system)

tool_path_planner/include/tool_path_planner/surface_walk_raster_generator.h

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,6 @@ class SurfaceWalkRasterGenerator : public PathGenerator
6464
static constexpr double DEFAULT_INTERSECTION_PLANE_HEIGHT = 0;
6565
static constexpr double DEFAULT_TOOL_OFFSET = 0;
6666
static constexpr bool DEFAULT_GENERATE_EXTRA_RASTERS = false;
67-
static constexpr bool DEFAULT_RASTER_WRT_GLOBAL_AXIS = false;
6867

6968
public:
7069
struct Config
@@ -77,7 +76,6 @@ class SurfaceWalkRasterGenerator : public PathGenerator
7776
double intersection_plane_height{ DEFAULT_INTERSECTION_PLANE_HEIGHT };
7877
double tool_offset{ DEFAULT_TOOL_OFFSET };
7978
bool generate_extra_rasters{ DEFAULT_GENERATE_EXTRA_RASTERS };
80-
bool raster_wrt_global_axes{ DEFAULT_RASTER_WRT_GLOBAL_AXIS };
8179
double cut_direction[3]{ 0, 0, 0 };
8280
bool debug{ false };
8381

tool_path_planner/src/surface_walk_raster_generator.cpp

Lines changed: 17 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -1229,40 +1229,41 @@ vtkSmartPointer<vtkPolyData> SurfaceWalkRasterGenerator::createStartCurve()
12291229
vtkSmartPointer<vtkPoints> pts = vtkSmartPointer<vtkPoints>::New();
12301230
line->SetPoints(pts);
12311231

1232-
Eigen::Vector3d max, min;
1232+
Eigen::Vector3d raster_axis, rotation_axis;
12331233
{
12341234
// Calculate the object-oriented bounding box to determine how wide a cutting plane should be
12351235
vtkSmartPointer<vtkOBBTree> obb_tree = vtkSmartPointer<vtkOBBTree>::New();
12361236
obb_tree->SetTolerance(0.001);
12371237
obb_tree->SetLazyEvaluation(0);
1238-
Eigen::Vector3d mid, corner, norm_size;
1238+
Eigen::Vector3d min, max, mid, corner, norm_size;
12391239
obb_tree->ComputeOBB(mesh_data_->GetPoints(), corner.data(), max.data(), mid.data(), min.data(), norm_size.data());
12401240

12411241
// Use the specified cut direction if it is not [0, 0, 0]
12421242
Eigen::Vector3d cut_dir{ config_.cut_direction };
12431243
if (!cut_dir.isApprox(Eigen::Vector3d::Zero()))
12441244
{
1245-
max = cut_dir.normalized() * max.norm();
1245+
// Project the cut direction onto the plane of the mesh defined by the average normal at [0, 0, 0]
1246+
Eigen::Hyperplane<double, 3> plane(avg_norm, 0.0);
1247+
raster_axis = plane.projection(cut_dir).normalized() * max.norm();
1248+
rotation_axis = avg_norm.normalized();
12461249
}
1247-
else
1250+
else if (norm_size[1] / norm_size[0] > 0.99)
12481251
{
12491252
// ComputeOBB uses PCA to find the principle axes, thus for square objects it returns the diagonals instead
1250-
// of the minimum bounding box. Compare the first and second axes to see if they are within 1% of each other
1251-
if (norm_size[1] / norm_size[0] > 0.99)
1252-
{
1253-
// if object is square, need to average max and mid in order to get the correct axes of the object
1254-
max = (max.normalized() + mid.normalized()) * max.norm();
1255-
}
1253+
// of the minimum bounding box. If the first and second axes are within 1% of each other, average max and mid
1254+
// to get the desired axes of the object
1255+
raster_axis = (max.normalized() + mid.normalized()) * max.norm();
1256+
}
1257+
else
1258+
{
1259+
// Simply use the max OBB axis as the raster axis and the min OBB axis as the rotation axis
1260+
raster_axis = max;
1261+
rotation_axis = min;
12561262
}
12571263
}
12581264

12591265
// Rotate the largest principal axis around the smallest principal axis by the specified angle
1260-
Eigen::Vector3d raster_axis = Eigen::AngleAxisd(config_.raster_rot_offset, min.normalized()) * max;
1261-
1262-
// TODO: Add the ability to define a rotation in mesh coordinates that is then projected onto the mesh plane
1263-
// if (config_.raster_wrt_global_axes)
1264-
// {
1265-
// }
1266+
raster_axis = Eigen::AngleAxisd(config_.raster_rot_offset, rotation_axis.normalized()) * raster_axis;
12661267

12671268
// Use raster_axis to create additional points for the starting curve
12681269
{

tool_path_planner/src/utilities.cpp

Lines changed: 9 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -152,8 +152,11 @@ bool toSurfaceWalkConfigMsg(noether_msgs::SurfaceWalkRasterGeneratorConfig& conf
152152
config_msg.min_hole_size = config.min_hole_size;
153153
config_msg.min_segment_size = config.min_segment_size;
154154
config_msg.raster_rot_offset = config.raster_rot_offset;
155-
config_msg.raster_wrt_global_axes = config.raster_wrt_global_axes;
156155
config_msg.generate_extra_rasters = config.generate_extra_rasters;
156+
157+
config_msg.cut_direction.x = config.cut_direction[0];
158+
config_msg.cut_direction.y = config.cut_direction[1];
159+
config_msg.cut_direction.z = config.cut_direction[2];
157160
return true;
158161
}
159162

@@ -208,8 +211,12 @@ bool toSurfaceWalkConfig(SurfaceWalkRasterGenerator::Config& config,
208211
config.min_hole_size = config_msg.min_hole_size;
209212
config.min_segment_size = config_msg.min_segment_size;
210213
config.raster_rot_offset = config_msg.raster_rot_offset;
211-
config.raster_wrt_global_axes = config_msg.raster_wrt_global_axes;
212214
config.generate_extra_rasters = config_msg.generate_extra_rasters;
215+
216+
config.cut_direction[0] = config_msg.cut_direction.x;
217+
config.cut_direction[1] = config_msg.cut_direction.y;
218+
config.cut_direction[2] = config_msg.cut_direction.z;
219+
213220
return true;
214221
}
215222

tool_path_planner/test/utest.cpp

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -370,7 +370,6 @@ TEST(IntersectTest, SurfaceWalkRasterRotationTest)
370370
tool.intersection_plane_height = 0.2; // 0.5 works best, not sure if this should be included in the tool
371371
tool.min_hole_size = 0.1;
372372
tool.raster_rot_offset = direction;
373-
tool.raster_wrt_global_axes = false;
374373
tool.debug = false;
375374
planner.setConfiguration(tool);
376375
runRasterRotationTest(planner, mesh);
@@ -393,7 +392,6 @@ TEST(IntersectTest, PlaneSlicerRasterRotationTest)
393392
// tool.tool_offset = 0.0; // currently unused
394393
tool.min_hole_size = 0.1;
395394
tool.raster_rot_offset = direction;
396-
// tool.raster_wrt_global_axes = false;
397395
// tool.debug = false;
398396
planner.setConfiguration(tool);
399397
runRasterRotationTest(planner, mesh);
@@ -532,7 +530,6 @@ TEST(IntersectTest, SurfaceWalkExtraRasterTest)
532530
tool.intersection_plane_height = 0.2; // 0.5 works best, not sure if this should be included in the tool
533531
tool.min_hole_size = 0.1;
534532
tool.raster_rot_offset = 0.0;
535-
tool.raster_wrt_global_axes = false;
536533
tool.generate_extra_rasters = false;
537534
tool.debug = false;
538535

0 commit comments

Comments
 (0)