Comments (5)
Yes, in this function:
I need to split the heuristic that search the best angle and the swath generator actually. As a way to solve your issue with the current code, you can use a F2CRobot
with a narrow width and then change the width of the swaths manually.
Just for curiosity, which is the purpouse of re-covering the same area systematically?
from fields2cover.
Yes. I suspect that specifying constant width / overhang is useful for other applications as well. But for me, it is an application where we like a bit of overlap (just ~5-10% of the robot implement width) to ensure we don't leave strips of land uncovered between swaths, to account for a bit of localization/controller variability etc.
As a way to solve your issue with the current code, you can use a F2CRobot with a narrow width and then change the width of the swaths manually.
I suspect if I do that, on the edge of the boundary the robot will overhang / violate the boundary right?
change the width of the swaths manually.
I am not sure what you mean / how that would help. Can you please clarify?
from fields2cover.
I suspect if I do that, on the edge of the boundary the robot will overhang / violate the boundary right?
The swath generator assume that you have headlands on the sides of the field. So even if the swaths go out of the mainland, you cover part of the headlands (without going outside).
As you can see, no checks are made if the area of the swaths go out of boundaries.
I am not sure what you mean / how that would help. Can you please clarify?
You can change the width of a swath with this function:
As F2CSwaths are containers of F2CSwath, you need to create a loop to change the width of each swath.
Other (easier) option is to modify the code on:
to:
float safe_perc = 0.1; // 10%
int n_swaths {static_cast<int>(ceil(field_width / (op_width - safe_perc)))};
auto seed_curve = rot_poly.getStraightLongCurve(
F2CPoint(rot_poly.getDimMinX(), rot_poly.getDimMinY()),
boost::math::constants::half_pi<double>());
F2CSwaths swaths;
for (int i = 0; i < n_swaths; ++i) {
auto path = F2CPoint(0.0, 0.0).rotateFromPoint(-angle,
seed_curve + F2CPoint(safe_perc / 2, 0.0) + F2CPoint(op_width - safe_perc, 0.0) * (i + 0.5));
swaths.append(path, poly, op_width);
}
from fields2cover.
Thanks for the insight @Gonzalo-Mier . I think I will probably test this out and PR the overlap input into the swath generator within the next few months. I will write it here in the issue when I get started.
As you can see, no checks are made if the area of the swaths go out of boundaries.
Yes I noticed that ! Is there a particular reason? It would be nice to have some sort of way to tell the system "never let the machine violate this boundary" for all types of generators (Swath Generator, Route Planner, Path Planner)
(Maybe this should be filed a separate issue / request)
from fields2cover.
Yes I noticed that ! Is there a particular reason? It would be nice to have some sort of way to tell the system "never let the machine violate this boundary" for all types of generators (Swath Generator, Route Planner, Path Planner)
The reasons is that we assume the headland generator part is used, and right now only constant width headland is provided. Boundaries are actually a huge constraint and we are also working on that part for future releases, but not solved yet.
from fields2cover.
Related Issues (20)
- catkin_make_isolated error HOT 10
- Max_Icc and Set Radius HOT 1
- How to get the swath endpoint HOT 3
- Not completely covering field HOT 1
- Nav2 Integration HOT 64
- Create Pypi package for the python interface
- Planning of Loops HOT 1
- Option to have turns happen inside the polygon when leaving the polygon shape is not permissible HOT 3
- Compilation steps are not rendered HOT 4
- Does not compile with clang HOT 1
- Is it possible to use this library to plan a coverage path connecting multiple convex polygons? HOT 4
- AerialmapDisplay HOT 3
- Headland width is not constant HOT 2
- questions about headland generator HOT 7
- Can F2C work with wgs84 coordinates? HOT 5
- Connecting between two fields HOT 5
- Deactivate headland HOT 2
- ROS2 support HOT 2
- Exported path discritization HOT 4
- New discretize_swath() function import issue to cpp/ROS2 package HOT 2
Recommend Projects
-
React
A declarative, efficient, and flexible JavaScript library for building user interfaces.
-
Vue.js
🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.
-
Typescript
TypeScript is a superset of JavaScript that compiles to clean JavaScript output.
-
TensorFlow
An Open Source Machine Learning Framework for Everyone
-
Django
The Web framework for perfectionists with deadlines.
-
Laravel
A PHP framework for web artisans
-
D3
Bring data to life with SVG, Canvas and HTML. 📊📈🎉
-
Recommend Topics
-
javascript
JavaScript (JS) is a lightweight interpreted programming language with first-class functions.
-
web
Some thing interesting about web. New door for the world.
-
server
A server is a program made to process requests and deliver data to clients.
-
Machine learning
Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.
-
Visualization
Some thing interesting about visualization, use data art
-
Game
Some thing interesting about game, make everyone happy.
Recommend Org
-
Facebook
We are working to build community through open source technology. NB: members must have two-factor auth.
-
Microsoft
Open source projects and samples from Microsoft.
-
Google
Google ❤️ Open Source for everyone.
-
Alibaba
Alibaba Open Source for everyone
-
D3
Data-Driven Documents codes.
-
Tencent
China tencent open source team.
from fields2cover.