Skip to content

Commit

Permalink
added arguments to planner_test. also planner_test now loops forever.
Browse files Browse the repository at this point in the history
  • Loading branch information
ClemensElflein committed Apr 24, 2024
1 parent 72ae645 commit 8ab6d50
Showing 1 changed file with 15 additions and 6 deletions.
21 changes: 15 additions & 6 deletions src/mower_utils/src/planner_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@ int main(int argc, char **argv) {
ros::NodeHandle n;
ros::NodeHandle paramNh("~");

int area_index = paramNh.param("area_index", 0);
int outline_count = paramNh.param("outline_count", 4);

ros::Publisher path_pub;

Expand All @@ -33,7 +35,7 @@ int main(int argc, char **argv) {


mower_map::GetMowingAreaSrv mapSrv;
mapSrv.request.index = 0;
mapSrv.request.index = area_index;

if (!mapClient.call(mapSrv)) {
ROS_ERROR_STREAM("Error loading mowing area");
Expand All @@ -42,16 +44,23 @@ int main(int argc, char **argv) {

slic3r_coverage_planner::PlanPath pathSrv;
pathSrv.request.angle = 0;
pathSrv.request.outline_count = 1;
pathSrv.request.outline_count = outline_count;
pathSrv.request.outline = mapSrv.response.area.area;
pathSrv.request.holes = mapSrv.response.area.obstacles;
pathSrv.request.fill_type = slic3r_coverage_planner::PlanPathRequest::FILL_LINEAR;
pathSrv.request.distance = 1.0;
pathSrv.request.distance = 0.13;
pathSrv.request.outer_offset = 0.05;

if (!pathClient.call(pathSrv)) {
ROS_ERROR_STREAM("Error getting path area");
return 1;
ros::Duration loop_time(1);
while(ros::ok()) {
if (!pathClient.call(pathSrv)) {
ROS_ERROR_STREAM("Error getting path area");
} else {
ROS_INFO_STREAM("Got path");
}
loop_time.sleep();
}

return 0;
}

0 comments on commit 8ab6d50

Please sign in to comment.