Skip to content

Commit

Permalink
Add outline_overlap_count parameter (#49)
Browse files Browse the repository at this point in the history
* Add OM_OUTLINE_OVERLAP_COUNT parameter and remove outline_count limit

The mower has a tendency to miss a small patch when turning at the
end of the fill lines.
This allows the fill path to overlap the given number of outlines to
ensure this patch is located on an already mowed area.

Also remove the outline count limit to allow a large number of outlines
to be used to generate something similar to a concentric pattern.

Requires ClemensElflein/slic3r_coverage_planner#2

* Use mower_config env vars for mower_logic in sim

* Update slic3r_coverage_planner
  • Loading branch information
olliewalsh authored Mar 10, 2024
1 parent b9d2df0 commit ae316bd
Show file tree
Hide file tree
Showing 6 changed files with 24 additions and 5 deletions.
2 changes: 1 addition & 1 deletion src/lib/slic3r_coverage_planner
3 changes: 2 additions & 1 deletion src/mower_logic/cfg/MowerLogic.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,8 @@ gen.add("undock_distance", double_t, 0, "Distance to drive back for undocking",
gen.add("docking_distance", double_t, 0, "Distance to drive forward during docking", 2, 0, 5)
gen.add("docking_approach_distance", double_t, 0, "Distance to approach docking point", 1.5, 0, 5)
gen.add("docking_retry_count", int_t, 0, "How often should we retry docking", 4, 1, 10)
gen.add("outline_count", int_t, 0, "Outline count to mow before filling", 3, 0, 10)
gen.add("outline_count", int_t, 0, "Outline count to mow before filling", 3, 0, 255)
gen.add("outline_overlap_count", int_t, 0, "Outlines to overlap with fill", 0, 0, 255)
gen.add("outline_offset", double_t, 0, "Additional outer outline offset, use positive values for safety, negative values to enlarge the area", 0.0, -1.0, 1.0)
gen.add("mow_angle_offset", double_t, 0, "Mowing angle offset", 0, -180, 180)
gen.add("mow_angle_offset_is_absolute", bool_t, 0, "If true then the offset is relative to East, if false then the offset is relative to the auto-detected angle.", False)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -171,6 +171,7 @@ bool MowingBehavior::create_mowing_plan(int area_index) {
slic3r_coverage_planner::PlanPath pathSrv;
pathSrv.request.angle = angle;
pathSrv.request.outline_count = config.outline_count;
pathSrv.request.outline_overlap_count = config.outline_overlap_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;
Expand Down
3 changes: 3 additions & 0 deletions src/open_mower/config/mower_config.sh.example
Original file line number Diff line number Diff line change
Expand Up @@ -90,6 +90,9 @@ export OM_UNDOCK_DISTANCE=2.0
# How many outlines should the mover drive. It's not recommended to set this below 4.
export OM_OUTLINE_COUNT=4

# How many outlines should the fill (lanes) overlap
export OM_OUTLINE_OVERLAP_COUNT=0

# Mowing angle offset -180 deg - +180 deg, 0 = east, -90 = north. If mowing angle offset is not absolute it gets added to the auto detected angle which is set by the first 2 m of recorded outline.
export OM_MOWING_ANGLE_OFFSET=0
export OM_MOWING_ANGLE_OFFSET_IS_ABSOLUTE=False
Expand Down
1 change: 1 addition & 0 deletions src/open_mower/launch/open_mower.launch
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
<param name="enable_mower" value="$(env OM_ENABLE_MOWER)"/>
<param name="battery_empty_voltage" value="$(env OM_BATTERY_EMPTY_VOLTAGE)"/>
<param name="outline_count" value="$(env OM_OUTLINE_COUNT)"/>
<param name="outline_overlap_count" value="$(optenv OM_OUTLINE_OVERLAP_COUNT 0)"/>
<param name="outline_offset" value="$(env OM_OUTLINE_OFFSET)"/>
<param name="mow_angle_offset" value="$(optenv OM_MOWING_ANGLE_OFFSET 0)"/>
<param name="mow_angle_offset_is_absolute" value="$(optenv OM_MOWING_ANGLE_OFFSET_IS_ABSOLUTE False)"/>
Expand Down
19 changes: 16 additions & 3 deletions src/open_mower/launch/sim_mower_logic.launch
Original file line number Diff line number Diff line change
Expand Up @@ -11,9 +11,22 @@
<node pkg="slic3r_coverage_planner" type="slic3r_coverage_planner" name="slic3r_coverage_planner" output="screen" required="true" />
<node pkg="mower_logic" type="mower_logic" name="mower_logic" output="log" required="true">
<param name="ignore_gps_errors" value="true"/>
<param name="outline_count" value="5"/>
<param name="gps_wait_time" value="0"/>
<param name="undock_distance" value="0.1"/>
<param name="automatic_mode" value="$(optenv OM_AUTOMATIC_MODE 0)"/>
<param name="docking_distance" value="$(env OM_DOCKING_DISTANCE)"/>
<param name="undock_distance" value="$(env OM_UNDOCK_DISTANCE)"/>
<param name="tool_width" value="$(env OM_TOOL_WIDTH)"/>
<param name="enable_mower" value="$(env OM_ENABLE_MOWER)"/>
<param name="battery_empty_voltage" value="$(env OM_BATTERY_EMPTY_VOLTAGE)"/>
<param name="outline_count" value="$(env OM_OUTLINE_COUNT)"/>
<param name="outline_overlap_count" value="$(optenv OM_OUTLINE_OVERLAP_COUNT 0)"/>
<param name="outline_offset" value="$(env OM_OUTLINE_OFFSET)"/>
<param name="mow_angle_offset" value="$(optenv OM_MOWING_ANGLE_OFFSET 0)"/>
<param name="mow_angle_offset_is_absolute" value="$(optenv OM_MOWING_ANGLE_OFFSET_IS_ABSOLUTE False)"/>
<param name="mow_angle_increment" value="$(optenv OM_MOWING_ANGLE_INCREMENT 0)"/>
<param name="battery_full_voltage" value="$(env OM_BATTERY_FULL_VOLTAGE)"/>
<param name="motor_hot_temperature" value="$(env OM_MOWING_MOTOR_TEMP_HIGH)"/>
<param name="motor_cold_temperature" value="$(env OM_MOWING_MOTOR_TEMP_LOW)"/>
</node>

<node pkg="twist_mux" type="twist_mux" name="twist_mux" output="screen">
Expand Down Expand Up @@ -42,4 +55,4 @@
<param name="sensor_ids" value="$(optenv OM_HEATMAP_SENSOR_IDS)" />
</node>

</launch>
</launch>

0 comments on commit ae316bd

Please sign in to comment.