Skip to content

Commit d71d630

Browse files
committed
Removed flag for planning wrt global axes; added cut direction to message
1 parent 0e5492c commit d71d630

File tree

2 files changed

+10
-11
lines changed

2 files changed

+10
-11
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/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

0 commit comments

Comments
 (0)