Skip to content

Commit d2a9dc5

Browse files
Feature new raster method, plane slicer (#82)
Co-authored-by: Levi Armstrong <levi.armstrong@gmail.com>
1 parent 5686421 commit d2a9dc5

File tree

10 files changed

+1283
-1
lines changed

10 files changed

+1283
-1
lines changed

.github/workflows/focal_build.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ jobs:
2222
UPSTREAM_WORKSPACE: 'dependencies_ros1.rosinstall'
2323
ROSDEP_SKIP_KEYS: "iwyu cmake_common_scripts"
2424
CCACHE_DIR: "/home/runner/work/noether/noether/Focal-Build/.ccache"
25-
TARGET_CMAKE_ARGS: "-DNURBS_FOUND=TRUE"
25+
TARGET_CMAKE_ARGS: "-DNURBS_FOUND=FALSE"
2626
DOCKER_IMAGE: "rosindustrial/noether:noetic"
2727
steps:
2828
- uses: actions/checkout@v2

noether_conversions/include/noether_conversions/noether_conversions.h

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -85,6 +85,24 @@ namespace noether_conversions {
8585
const std::tuple<float,float,float,float,float,float>& offset = std::make_tuple(
8686
0.0, 0.0, 0.0, 0.0, 0.0, 0.0));
8787

88+
visualization_msgs::MarkerArray convertToArrowMarkers(const std::vector<geometry_msgs::PoseArray>& path,
89+
const std::string& frame_id,
90+
const std::string& ns,
91+
const std::size_t start_id = 1,
92+
const float arrow_diameter = 0.002,
93+
const float point_size = 0.01,
94+
const std::tuple<float, float, float, float, float, float>&offset =
95+
std::make_tuple(0.0, 0.0, 0.0, 0.0, 0.0, 0.0));
96+
97+
visualization_msgs::MarkerArray convertToArrowMarkers(const noether_msgs::ToolRasterPath& toolpath,
98+
const std::string& frame_id,
99+
const std::string& ns,
100+
const std::size_t start_id = 1,
101+
const float arrow_diameter = 0.002,
102+
const float point_size = 0.01,
103+
const std::tuple<float, float, float, float, float, float>&offset =
104+
std::make_tuple(0.0, 0.0, 0.0, 0.0, 0.0, 0.0));
105+
88106
visualization_msgs::MarkerArray convertToDottedLineMarker(const noether_msgs::ToolRasterPath& toolpath,
89107
const std::string& frame_id,
90108
const std::string& ns,

noether_conversions/src/noether_conversions.cpp

Lines changed: 77 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -272,6 +272,83 @@ visualization_msgs::MarkerArray convertToAxisMarkers(const std::vector<geometry_
272272
return std::move(markers);
273273
}
274274

275+
visualization_msgs::MarkerArray convertToArrowMarkers(const noether_msgs::ToolRasterPath& toolpath,
276+
const std::string& frame_id,
277+
const std::string& ns,
278+
const std::size_t start_id,
279+
const float arrow_diameter,
280+
const float point_size,
281+
const std::tuple<float, float, float, float, float, float>&offset)
282+
{
283+
return convertToArrowMarkers(toolpath.paths,frame_id, ns, start_id, arrow_diameter, point_size, offset);
284+
}
285+
286+
visualization_msgs::MarkerArray convertToArrowMarkers(const std::vector<geometry_msgs::PoseArray>& path,
287+
const std::string& frame_id,
288+
const std::string& ns,
289+
const std::size_t start_id,
290+
const float arrow_diameter,
291+
const float point_size,
292+
const std::tuple<float, float, float, float, float, float>&offset)
293+
{
294+
visualization_msgs::MarkerArray markers_msgs;
295+
visualization_msgs::Marker arrow_marker, points_marker;
296+
const geometry_msgs::Pose pose_msg = pose3DtoPoseMsg(offset);
297+
298+
// configure arrow marker
299+
arrow_marker.action = arrow_marker.ADD;
300+
std::tie(arrow_marker.color.r, arrow_marker.color.g, arrow_marker.color.b, arrow_marker.color.a) = std::make_tuple(1.0, 1.0, 0.2, 1.0);
301+
arrow_marker.header.frame_id = frame_id;
302+
arrow_marker.type = arrow_marker.ARROW;
303+
arrow_marker.id = start_id;
304+
arrow_marker.lifetime = ros::Duration(0);
305+
arrow_marker.ns = ns;
306+
std::tie(arrow_marker.scale.x, arrow_marker.scale.y, arrow_marker.scale.z) = std::make_tuple(arrow_diameter, 4.0 * arrow_diameter, 4.0 * arrow_diameter);
307+
308+
309+
// configure point marker
310+
points_marker = arrow_marker;
311+
points_marker.type = points_marker.POINTS;
312+
points_marker.ns = ns;
313+
points_marker.pose = pose_msg;
314+
std::tie(points_marker.color.r, points_marker.color.g, points_marker.color.b, points_marker.color.a) = std::make_tuple(0.1, .8, 0.2, 1.0);
315+
std::tie(points_marker.scale.x, points_marker.scale.y, points_marker.scale.z) = std::make_tuple(point_size,point_size,point_size);
316+
317+
auto transformPoint = [](const geometry_msgs::Pose& pose_msg, const geometry_msgs::Point& p_msg) -> geometry_msgs::Point{
318+
auto new_p_msg = p_msg;
319+
Eigen::Isometry3d transform;
320+
Eigen::Vector3d p, new_p;
321+
tf::poseMsgToEigen(pose_msg,transform);
322+
tf::pointMsgToEigen(p_msg, p);
323+
new_p = transform * p;
324+
tf::pointEigenToMsg(new_p, new_p_msg);
325+
return new_p_msg;
326+
};
327+
328+
int id_counter = static_cast<int>(start_id);
329+
for(auto& poses : path)
330+
{
331+
points_marker.points.clear();
332+
points_marker.points.push_back(poses.poses.front().position);
333+
for(std::size_t i = 1; i < poses.poses.size(); i++)
334+
{
335+
arrow_marker.points.clear();
336+
geometry_msgs::Point p_start = transformPoint(pose_msg, poses.poses[i - 1].position);
337+
geometry_msgs::Point p_end = transformPoint(pose_msg,poses.poses[i].position);
338+
arrow_marker.points.push_back(p_start);
339+
arrow_marker.points.push_back(p_end);
340+
arrow_marker.id = (++id_counter);
341+
markers_msgs.markers.push_back(arrow_marker);
342+
}
343+
points_marker.points.push_back(poses.poses.back().position);
344+
345+
points_marker.id = (++id_counter);
346+
markers_msgs.markers.push_back(points_marker);
347+
}
348+
349+
return markers_msgs;
350+
}
351+
275352
visualization_msgs::MarkerArray convertToDottedLineMarker(const noether_msgs::ToolRasterPath& toolpath,
276353
const std::string& frame_id,
277354
const std::string& ns,
Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,15 @@
1+
<?xml version="1.0"?>
2+
<launch>
3+
<arg name="mesh_file" />
4+
<node launch-prefix="" name="rastering_demo_node" pkg="noether_examples" type="rastering_demo_node" output="screen">
5+
<param name="mesh_file" value="$(arg mesh_file)"/>
6+
<rosparam ns="plane_slicer_rastering">
7+
raster_spacing: 0.05
8+
point_spacing: 0.02
9+
raster_rot_offset: 0.0
10+
min_hole_size: 0.02
11+
min_segment_size: 0.01
12+
search_radius: 0.02
13+
</rosparam>
14+
</node>
15+
</launch>
Lines changed: 221 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,221 @@
1+
/**
2+
* @author Jorge Nicho <jrgnichodevel@gmail.com>
3+
* @file rastering_demo_node.cpp
4+
* @date Dec 27, 2019
5+
* @copyright Copyright (c) 2019, Southwest Research Institute
6+
*
7+
* @par License
8+
* Software License Agreement (Apache License)
9+
* @par
10+
* Licensed under the Apache License, Version 2.0 (the "License");
11+
* you may not use this file except in compliance with the License.
12+
* You may obtain a copy of the License at
13+
* http://www.apache.org/licenses/LICENSE-2.0
14+
* @par
15+
* Unless required by applicable law or agreed to in writing, software
16+
* distributed under the License is distributed on an "AS IS" BASIS,
17+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
18+
* See the License for the specific language governing permissions and
19+
* limitations under the License.
20+
*/
21+
22+
#include <ros/ros.h>
23+
#include <XmlRpcException.h>
24+
#include <boost/format.hpp>
25+
#include <boost/filesystem.hpp>
26+
#include <noether_conversions/noether_conversions.h>
27+
#include <tool_path_planner/plane_slicer_raster_generator.h>
28+
#include <visualization_msgs/MarkerArray.h>
29+
#include <actionlib/client/simple_action_client.h>
30+
#include <console_bridge/console.h>
31+
32+
using RGBA = std::tuple<double,double,double,double>;
33+
34+
static const std::string DEFAULT_FRAME_ID = "world";
35+
static const std::string RASTER_LINES_MARKERS_TOPIC ="raster_lines";
36+
static const std::string RASTER_POSES_MARKERS_TOPIC ="raster_poses";
37+
static const std::string RASTER_PATH_NS = "raster_";
38+
static const std::string INPUT_MESH_NS = "input_mesh";
39+
static const RGBA RAW_MESH_RGBA = std::make_tuple(0.6, 0.6, 1.0, 1.0);
40+
41+
class Rasterer
42+
{
43+
public:
44+
45+
Rasterer(ros::NodeHandle nh):
46+
nh_(nh)
47+
{
48+
raster_lines_markers_pub_ = nh_.advertise<visualization_msgs::MarkerArray>(RASTER_LINES_MARKERS_TOPIC,1);
49+
raster_poses_markers_pub_ = nh_.advertise<visualization_msgs::MarkerArray>(RASTER_POSES_MARKERS_TOPIC,1);
50+
}
51+
52+
~Rasterer()
53+
{
54+
55+
}
56+
57+
bool loadConfig(tool_path_planner::PlaneSlicerRasterGenerator::Config& config)
58+
{
59+
ros::NodeHandle ph("~");
60+
XmlRpc::XmlRpcValue cfg;
61+
if(!ph.getParam("plane_slicer_rastering", cfg))
62+
{
63+
return false;
64+
}
65+
66+
/*
67+
* load configuration into the following struct type
68+
struct Config
69+
{
70+
double raster_spacing = 0.04;
71+
double point_spacing = 0.01;
72+
double raster_rot_offset = 0.0;
73+
double min_hole_size = 0.01;
74+
double min_segment_size = 0.01;
75+
double search_radius = 0.01;
76+
};
77+
*/
78+
79+
std::vector<std::string> field_names = {"raster_spacing",
80+
"point_spacing",
81+
"raster_rot_offset",
82+
"min_hole_size",
83+
"min_segment_size",
84+
"search_radius"};
85+
if(!std::all_of(field_names.begin(), field_names.end(), [&cfg](const std::string& f){
86+
return cfg.hasMember(f);
87+
}))
88+
{
89+
ROS_ERROR("Failed to find one or more members");
90+
}
91+
92+
std::size_t idx = 0;
93+
try
94+
{
95+
config.raster_spacing = static_cast<double>(cfg[field_names[idx++]]);
96+
config.point_spacing = static_cast<double>(cfg[field_names[idx++]]);
97+
config.raster_rot_offset = static_cast<double>(cfg[field_names[idx++]]);
98+
config.min_hole_size = static_cast<double>(cfg[field_names[idx++]]);
99+
config.min_segment_size = static_cast<double>(cfg[field_names[idx++]]);
100+
config.search_radius = static_cast<double>(cfg[field_names[idx++]]);
101+
}
102+
catch(XmlRpc::XmlRpcException& e)
103+
{
104+
ROS_ERROR_STREAM(e.getMessage());
105+
}
106+
return true;
107+
}
108+
109+
bool run()
110+
{
111+
using namespace noether_conversions;
112+
113+
// loading parameters
114+
ros::NodeHandle ph("~");
115+
std::string mesh_file;
116+
if(!ph.getParam("mesh_file",mesh_file))
117+
{
118+
ROS_ERROR("Failed to load one or more parameters");
119+
return false;
120+
}
121+
122+
ROS_INFO("Got mesh file %s", mesh_file.c_str());
123+
124+
// get configuration
125+
tool_path_planner::PlaneSlicerRasterGenerator::Config config;
126+
if(!loadConfig(config))
127+
{
128+
ROS_WARN("Failed to load configuration, using default parameters");
129+
}
130+
131+
markers_publish_timer_ = nh_.createTimer(ros::Duration(0.5),[&](const ros::TimerEvent& e){
132+
if(!line_markers_.markers.empty())
133+
{
134+
raster_lines_markers_pub_.publish(line_markers_);
135+
}
136+
137+
if(!poses_markers_.markers.empty())
138+
{
139+
raster_poses_markers_pub_.publish(poses_markers_);
140+
}
141+
});
142+
143+
shape_msgs::Mesh mesh_msg;
144+
if(!noether_conversions::loadPLYFile(mesh_file,mesh_msg))
145+
{
146+
ROS_ERROR("Failed to read file %s",mesh_file.c_str());
147+
return false;
148+
}
149+
line_markers_.markers.push_back(createMeshMarker(mesh_file,INPUT_MESH_NS,DEFAULT_FRAME_ID,RAW_MESH_RGBA));
150+
151+
152+
153+
// rastering
154+
tool_path_planner::PlaneSlicerRasterGenerator raster_gen;
155+
boost::optional< std::vector<noether_msgs::ToolRasterPath> > temp = raster_gen.generate(mesh_msg,config);
156+
if(!temp)
157+
{
158+
ROS_ERROR("Failed to generate rasters");
159+
return false;
160+
}
161+
std::vector<noether_msgs::ToolRasterPath> raster_paths = *temp;
162+
163+
ROS_INFO("Found %lu rasters",raster_paths.size());
164+
165+
for(std::size_t i = 0; i < raster_paths.size(); i++)
166+
{
167+
ROS_INFO("Raster %lu contains %lu segments",i, raster_paths[i].paths.size());
168+
for(std::size_t j = 0; j < raster_paths[i].paths.size(); j++)
169+
{
170+
std::cout<<"\tSegment "<< j << " contains "<< raster_paths[i].paths[j].poses.size() << " points"<<std::endl;
171+
172+
173+
std::string ns = RASTER_PATH_NS + std::to_string(i) + std::string("_s[") + std::to_string(j) + std::string("]") ;
174+
visualization_msgs::MarkerArray edge_path_axis_markers = convertToAxisMarkers({raster_paths[i].paths[j]},
175+
DEFAULT_FRAME_ID,
176+
ns);
177+
178+
visualization_msgs::MarkerArray edge_path_line_markers = convertToArrowMarkers({raster_paths[i].paths[j]},
179+
DEFAULT_FRAME_ID,
180+
ns);
181+
182+
poses_markers_.markers.insert( poses_markers_.markers.end(),
183+
edge_path_axis_markers.markers.begin(), edge_path_axis_markers.markers.end());
184+
line_markers_.markers.insert( line_markers_.markers.end(),
185+
edge_path_line_markers.markers.begin(), edge_path_line_markers.markers.end());
186+
}
187+
}
188+
return true;
189+
}
190+
191+
private:
192+
ros::NodeHandle nh_;
193+
ros::Timer markers_publish_timer_;
194+
ros::Publisher raster_lines_markers_pub_;
195+
ros::Publisher raster_poses_markers_pub_;
196+
visualization_msgs::MarkerArray line_markers_;
197+
visualization_msgs::MarkerArray poses_markers_;
198+
199+
};
200+
201+
int main(int argc, char** argv)
202+
{
203+
ros::init(argc,argv,"halfedge_finder");
204+
console_bridge::setLogLevel(console_bridge::LogLevel::CONSOLE_BRIDGE_LOG_DEBUG);
205+
ros::NodeHandle nh;
206+
ros::AsyncSpinner spinner(2);
207+
spinner.start();
208+
Rasterer edge_finder(nh);
209+
if(!edge_finder.run())
210+
{
211+
return -1;
212+
}
213+
ros::waitForShutdown();
214+
return 0;
215+
}
216+
217+
218+
219+
220+
221+

tool_path_planner/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -64,6 +64,7 @@ include_directories(
6464
add_library(${PROJECT_NAME}
6565
src/raster_path_generator.cpp
6666
src/raster_tool_path_planner.cpp
67+
src/plane_slicer_raster_generator.cpp
6768
src/edge_path_generator.cpp
6869
src/halfedge_boundary_finder.cpp
6970
src/utilities.cpp

0 commit comments

Comments
 (0)