diff --git a/virtual_maize_field/.gitignore b/virtual_maize_field/.gitignore index c4d495c..14ff79f 100644 --- a/virtual_maize_field/.gitignore +++ b/virtual_maize_field/.gitignore @@ -28,3 +28,4 @@ CATKIN_IGNORE # Ignore generated files worlds/generated.world Media/models/virtual_maize_field_heightmap.png +generated_minimap.png diff --git a/virtual_maize_field/README.md b/virtual_maize_field/README.md index b9af188..4568cec 100644 --- a/virtual_maize_field/README.md +++ b/virtual_maize_field/README.md @@ -27,10 +27,7 @@ Additional you'll need the following packages: # melodic rosdep install virtual_maize_field sudo apt install python3-pip -sudo pip3 install -U jinja2 rospkg -sudo pip3 install opencv-python -sudo pip3 install matplotlib -sudo pip3 install shapely +sudo pip3 install -U jinja2 rospkg opencv-python matplotlib shapely # noetic rosdep install virtual_maize_field @@ -138,12 +135,12 @@ In the script folder, bash files to generate sample worlds are located. The para |:---- |:--------- |:----------- | | *create_task_1.sh* | `--row_length 10 --rows_left 0 --rows_right 11 --rows_curve_budget 0.78539816339 --row_segments straight,curved --row_segment_curved_radius_min 4.0 --row_segment_curved_radius_max 5.0` | Task 1, curved rows without holes | | *create_task_1_mini.sh* | `--row_length 5 --rows_left 0 --rows_right 5 --rows_curve_budget 0.78539816339 --row_segments straight,curved --row_segment_curved_radius_min 4.0 --row_segment_curved_radius_max 5.0` | A smaller version of task 1, requiring less computer power | -| *create_task_2.sh* | `--row_length 7 --rows_left 0 --rows_right 11 --row_segments straight --hole_prob 0.04 --max_hole_size 7` | Task 2, straight rows with holes | -| *create_task_2_mini.sh* | `--row_length 3.5 --rows_left 0 --rows_right 7 --row_segments straight --hole_prob 0.04 --max_hole_size 7` | A smaller version of task 2, requiring less computer power | -| *create_task_3.sh* | `--row_length 7 --rows_left 0 --rows_right 11 --row_segments straight --hole_prob 0.04 --max_hole_size 7 --litters 5 --weeds 5 --ghost_objects true` | Task 3, similar crop rows as in task_2 but with cans, bottles and weeds spread throughout the field. The cans, bottles and weeds have no collision box and are static. | -| *create_task_3_mini.sh* | `--row_length 3.5 --rows_left 0 --rows_right 7 --row_segments straight --hole_prob 0.04 --max_hole_size 7 --litters 5 --weeds 5 --ghost_objects true` | A smaller version of task 3, requiring less computer power | -| *create_task_4.sh* | `--row_length 7 --rows_left 0 --rows_right 11 --row_segments straight --hole_prob 0.04 --max_hole_size 7 --litters 5 --weeds 5` | Task 4, similar crop rows as in task_2 but with cans, bottles and weeds spread throughout the field. The cans, bottles and weeds have a collision box and can be picked up. | -| *create_task_4_mini.sh* | `--row_length 3.5 --rows_left 0 --rows_right 7 --row_segments straight --hole_prob 0.04 --max_hole_size 7 --litters 5 --weeds 5` | A smaller version of task 4, requiring less computer power | +| *create_task_2.sh* | `--row_length 7 --rows_left 0 --rows_right 11 --row_segments straight --hole_prob 0.04 --hole_size_max 7` | Task 2, straight rows with holes | +| *create_task_2_mini.sh* | `--row_length 3.5 --rows_left 0 --rows_right 7 --row_segments straight --hole_prob 0.04 --hole_size_max 7` | A smaller version of task 2, requiring less computer power | +| *create_task_3.sh* | `--row_length 7 --rows_left 0 --rows_right 11 --row_segments straight --hole_prob 0.04 --hole_size_max 7 --litters 5 --weeds 5 --ghost_objects true` | Task 3, similar crop rows as in task_2 but with cans, bottles and weeds spread throughout the field. The cans, bottles and weeds have no collision box and are static. | +| *create_task_3_mini.sh* | `--row_length 3.5 --rows_left 0 --rows_right 7 --row_segments straight --hole_prob 0.04 --hole_size_max 7 --litters 5 --weeds 5 --ghost_objects true` | A smaller version of task 3, requiring less computer power | +| *create_task_4.sh* | `--row_length 7 --rows_left 0 --rows_right 11 --row_segments straight --hole_prob 0.04 --hole_size_max 7 --litters 5 --weeds 5` | Task 4, similar crop rows as in task_2 but with cans, bottles and weeds spread throughout the field. The cans, bottles and weeds have a collision box and can be picked up. | +| *create_task_4_mini.sh* | `--row_length 3.5 --rows_left 0 --rows_right 7 --row_segments straight --hole_prob 0.04 --hole_size_max 7 --litters 5 --weeds 5` | A smaller version of task 4, requiring less computer power | ## Launching worlds The launch file to launch the worlds is called `simulation.launch`. You can launch the launch file by running `roslaunch virtual_maize_field simulation.launch`. By default the launch file will launch `generated_world.world`. You can launch any world by using the `world_name` arg. e.g. `roslaunch virtual_maize_field simulation.launch world_name:=simple_row_level_1.world`. diff --git a/virtual_maize_field/scripts/create_task_1.sh b/virtual_maize_field/scripts/create_task_1.sh index da35296..98a6e3b 100644 --- a/virtual_maize_field/scripts/create_task_1.sh +++ b/virtual_maize_field/scripts/create_task_1.sh @@ -1,6 +1,4 @@ # remove old gazebo cache file, so gazebo is forced to use the new height map. -rm -r ~/.gazebo/paging/virtual_maize_field_heightmap - rosrun virtual_maize_field generate_world.py \ --row_length 10 \ --rows_left 0 \ @@ -9,5 +7,3 @@ rosrun virtual_maize_field generate_world.py \ --row_segments straight,curved \ --row_segment_curved_radius_min 4.0 \ --row_segment_curved_radius_max 5.0 - - diff --git a/virtual_maize_field/scripts/create_task_1_mini.sh b/virtual_maize_field/scripts/create_task_1_mini.sh index f931cfe..e2f542c 100644 --- a/virtual_maize_field/scripts/create_task_1_mini.sh +++ b/virtual_maize_field/scripts/create_task_1_mini.sh @@ -1,6 +1,4 @@ # remove old gazebo cache file, so gazebo is forced to use the new height map. -rm -r ~/.gazebo/paging/virtual_maize_field_heightmap - rosrun virtual_maize_field generate_world.py \ --row_length 5 \ --rows_left 0 \ @@ -9,5 +7,3 @@ rosrun virtual_maize_field generate_world.py \ --row_segments straight,curved \ --row_segment_curved_radius_min 4.0 \ --row_segment_curved_radius_max 5.0 - - diff --git a/virtual_maize_field/scripts/create_task_2.sh b/virtual_maize_field/scripts/create_task_2.sh index f23e8e2..defcc02 100644 --- a/virtual_maize_field/scripts/create_task_2.sh +++ b/virtual_maize_field/scripts/create_task_2.sh @@ -1,10 +1,8 @@ # remove old gazebo cache file, so gazebo is forced to use the new height map. -rm -r ~/.gazebo/paging/virtual_maize_field_heightmap - rosrun virtual_maize_field generate_world.py \ --row_length 7 \ --rows_left 0 \ --rows_right 11 \ --row_segments straight \ --hole_prob 0.04 \ ---max_hole_size 7 +--hole_size_max 7 diff --git a/virtual_maize_field/scripts/create_task_2_mini.sh b/virtual_maize_field/scripts/create_task_2_mini.sh index 2c9c210..032d088 100644 --- a/virtual_maize_field/scripts/create_task_2_mini.sh +++ b/virtual_maize_field/scripts/create_task_2_mini.sh @@ -1,10 +1,8 @@ # remove old gazebo cache file, so gazebo is forced to use the new height map. -rm -r ~/.gazebo/paging/virtual_maize_field_heightmap - rosrun virtual_maize_field generate_world.py \ --row_length 3.5 \ --rows_left 0 \ --rows_right 7 \ --row_segments straight \ --hole_prob 0.04 \ ---max_hole_size 7 +--hole_size_max 7 diff --git a/virtual_maize_field/scripts/create_task_3.sh b/virtual_maize_field/scripts/create_task_3.sh index 2532b66..9c238c9 100644 --- a/virtual_maize_field/scripts/create_task_3.sh +++ b/virtual_maize_field/scripts/create_task_3.sh @@ -1,13 +1,11 @@ # remove old gazebo cache file, so gazebo is forced to use the new height map. -rm -r ~/.gazebo/paging/virtual_maize_field_heightmap - rosrun virtual_maize_field generate_world.py \ --row_length 7 \ --rows_left 0 \ --rows_right 11 \ --row_segments straight \ --hole_prob 0.04 \ ---max_hole_size 7 \ +--hole_size_max 7 \ --litters 5 \ --weeds 5 \ --ghost_objects true diff --git a/virtual_maize_field/scripts/create_task_3_mini.sh b/virtual_maize_field/scripts/create_task_3_mini.sh index f1c29e8..b0db29b 100644 --- a/virtual_maize_field/scripts/create_task_3_mini.sh +++ b/virtual_maize_field/scripts/create_task_3_mini.sh @@ -1,13 +1,11 @@ # remove old gazebo cache file, so gazebo is forced to use the new height map. -rm -r ~/.gazebo/paging/virtual_maize_field_heightmap - rosrun virtual_maize_field generate_world.py \ --row_length 3.5 \ --rows_left 0 \ --rows_right 7 \ --row_segments straight \ --hole_prob 0.04 \ ---max_hole_size 7 \ +--hole_size_max 7 \ --litters 5 \ --weeds 5 \ --ghost_objects true diff --git a/virtual_maize_field/scripts/create_task_4.sh b/virtual_maize_field/scripts/create_task_4.sh index 4769ffa..bb2a463 100644 --- a/virtual_maize_field/scripts/create_task_4.sh +++ b/virtual_maize_field/scripts/create_task_4.sh @@ -1,12 +1,10 @@ # remove old gazebo cache file, so gazebo is forced to use the new height map. -rm -r ~/.gazebo/paging/virtual_maize_field_heightmap - rosrun virtual_maize_field generate_world.py \ --row_length 7 \ --rows_left 0 \ --rows_right 11 \ --row_segments straight \ --hole_prob 0.04 \ ---max_hole_size 7 \ +--hole_size_max 7 \ --litters 5 \ --weeds 5 diff --git a/virtual_maize_field/scripts/create_task_4_mini.sh b/virtual_maize_field/scripts/create_task_4_mini.sh index 84f78c3..f521f4d 100644 --- a/virtual_maize_field/scripts/create_task_4_mini.sh +++ b/virtual_maize_field/scripts/create_task_4_mini.sh @@ -1,12 +1,10 @@ # remove old gazebo cache file, so gazebo is forced to use the new height map. -rm -r ~/.gazebo/paging/virtual_maize_field_heightmap - rosrun virtual_maize_field generate_world.py \ --row_length 3.5 \ --rows_left 0 \ --rows_right 7 \ --row_segments straight \ --hole_prob 0.04 \ ---max_hole_size 7 \ +--hole_size_max 7 \ --litters 5 \ --weeds 5 diff --git a/virtual_maize_field/scripts/field_2d_generator.py b/virtual_maize_field/scripts/field_2d_generator.py index bd417eb..970497a 100644 --- a/virtual_maize_field/scripts/field_2d_generator.py +++ b/virtual_maize_field/scripts/field_2d_generator.py @@ -17,7 +17,6 @@ def __init__(self, world_description=WorldDescription()): self.wd = world_description np.random.seed(self.wd.structure["params"]["seed"]) - def render_matplotlib(self): # Segments for segment in self.segments: @@ -26,16 +25,18 @@ def render_matplotlib(self): # Plants plt.scatter(self.crop_placements[:, 0], self.crop_placements[:, 1], color="c", marker=".") - def plot_field(self): plt.plot(*self.field_poly.exterior.xy) plt.scatter(self.crop_placements[:, 0], self.crop_placements[:, 1], color="g", marker=".") if self.weed_placements.ndim == 2: - plt.scatter(self.weed_placements[:, 0], self.weed_placements[:, 1], color="r", marker=".") + plt.scatter( + self.weed_placements[:, 0], self.weed_placements[:, 1], color="r", marker="." + ) if self.litter_placements.ndim == 2: - plt.scatter(self.litter_placements[:, 0], self.litter_placements[:, 1], color="b", marker=".") - self.mini_map = plt - + plt.scatter( + self.litter_placements[:, 0], self.litter_placements[:, 1], color="b", marker="." + ) + self.minimap = plt def generate(self): self.chain_segments() @@ -46,7 +47,6 @@ def generate(self): self.render_to_template() self.plot_field() return [self.sdf, self.heightmap] - def chain_segments(self): # Generate start points @@ -113,20 +113,20 @@ def chain_segments(self): self.rows = [] for row in self.crop_placements: row = np.vstack(row) - + # generate indexes of the end of the hole probs = np.random.sample(row.shape[0]) probs = probs < self.wd.structure["params"]["hole_prob"] - + # iterate in reverse order, and remove plants in the holes - i = probs.shape[0]-1 - while i > 0 : + i = probs.shape[0] - 1 + while i > 0: if probs[i]: - hole_size = np.random.randint(1, self.wd.structure["params"]["max_hole_size"]) - row = np.delete(row, slice(max(0,i-hole_size), i), axis=0) + hole_size = np.random.randint(1, self.wd.structure["params"]["hole_size_max"]) + row = np.delete(row, slice(max(0, i - hole_size), i), axis=0) i = i - hole_size - i = i -1 + i = i - 1 self.rows.append(row) # Add bounden noise to placements @@ -142,15 +142,14 @@ def chain_segments(self): x += bg.get() y += bg.get() new_row.append([x, y]) - - self.rows[i] = np.array(new_row) + self.rows[i] = np.array(new_row) # Because the heightmap must be square and has to have a side length of 2^n + 1 # this means that we could have smaller maps, by centering the placements around 0,0 def center_plants(self): self.crop_placements = np.vstack(self.rows) - + x_min = self.crop_placements[:, 0].min() y_min = self.crop_placements[:, 1].min() @@ -159,51 +158,58 @@ def center_plants(self): for i in range(len(self.rows)): self.rows[i] -= np.array([x_min, y_min]) - self.rows[i] -= np.array([x_max, y_max]) / 2 - + self.rows[i] -= np.array([x_max, y_max]) / 2 # The function calculates the placements of the weed plants and # stores them under self.weeds : np.array([[x,y],[x,y],...]) def place_objects(self): def random_points_within(poly, num_points): min_x, min_y, max_x, max_y = poly.bounds - + points = [] - + while len(points) < num_points: np_point = [np.random.uniform(min_x, max_x), np.random.uniform(min_y, max_y)] random_point = shapely.geometry.Point(np_point) - if (random_point.within(poly)): + if random_point.within(poly): points.append(np_point) - + return np.array(points) - + # Get outher boundary of the of the crops outer_plants = np.concatenate((self.rows[0], np.flipud(self.rows[-1]))) self.field_poly = geometry.Polygon(outer_plants) # place x_nr of weeds within the field area - self.weed_placements = random_points_within(self.field_poly, self.wd.structure["params"]["weeds"]) - weed_types = np.random.choice(self.wd.structure["params"]["weed_types"].split(","), self.wd.structure["params"]["weeds"]) - + self.weed_placements = random_points_within( + self.field_poly, self.wd.structure["params"]["weeds"] + ) + weed_types = np.random.choice( + self.wd.structure["params"]["weed_types"].split(","), + self.wd.structure["params"]["weeds"], + ) + # place y_nr of litter within the field area - self.litter_placements = random_points_within(self.field_poly, self.wd.structure["params"]["litters"]) - litter_types = np.random.choice(self.wd.structure["params"]["litter_types"].split(","), self.wd.structure["params"]["litters"]) - + self.litter_placements = random_points_within( + self.field_poly, self.wd.structure["params"]["litters"] + ) + litter_types = np.random.choice( + self.wd.structure["params"]["litter_types"].split(","), + self.wd.structure["params"]["litters"], + ) + # TODO Thijs # place start marker at the beginning of the field - + # TODO Thijs # place location markers at the desginated locations - self.object_placements = np.concatenate((self.weed_placements, self.litter_placements)) self.object_types = np.concatenate((weed_types, litter_types)) - def generate_ground(self): self.crop_placements = np.vstack(self.rows) - + if self.object_placements.ndim == 2: self.placements = np.concatenate((self.crop_placements, self.object_placements), axis=0) else: @@ -217,10 +223,8 @@ def generate_ground(self): metric_width = metric_x_max - metric_x_min + 4 metric_height = metric_y_max - metric_y_min + 4 - resolution = self.wd.structure["params"]["dem_res"] - min_image_size = int( - np.ceil(max(metric_width / resolution, metric_height / resolution)) - ) + resolution = self.wd.structure["params"]["ground_resolution"] + min_image_size = int(np.ceil(max(metric_width / resolution, metric_height / resolution))) image_size = int(2 ** np.ceil(np.log2(min_image_size))) + 1 # Generate noise @@ -251,7 +255,7 @@ def generate_ground(self): height = heightmap[py, px] heightmap = cv2.circle(heightmap, (px, py), 2, height, -1) self.placements_ground_height.append( - self.wd.structure["params"]["ground_max_elevation"] * height + self.wd.structure["params"]["ground_elevation_max"] * height ) # Convert to grayscale @@ -264,16 +268,14 @@ def generate_ground(self): metric_y_min - 2 + 0.5 * self.metric_size, ] - def fix_gazebo(self): # move the plants to the center of the flat circles - self.crop_placements -= 0.01 - self.object_placements -= 0.01 + self.crop_placements -= self.wd.structure["params"]["ground_resolution"] / 2 + self.object_placements -= self.wd.structure["params"]["ground_resolution"] / 2 # set heightmap position to origin self.heightmap_position = [0, 0] - def render_to_template(self): def into_dict(xy, ground_height, radius, height, mass, m_type, index): coordinate = dict() @@ -289,8 +291,7 @@ def into_dict(xy, ground_height, radius, height, mass, m_type, index): coordinate["z"] = ground_height coordinate["radius"] = ( radius - + (2 * np.random.rand() - 1) - * self.wd.structure["params"]["plant_radius_noise"] + + (2 * np.random.rand() - 1) * self.wd.structure["params"]["plant_radius_noise"] ) if coordinate["type"] == "cylinder": coordinate["height"] = height @@ -307,11 +308,11 @@ def into_dict(xy, ground_height, radius, height, mass, m_type, index): self.wd.structure["params"]["plant_height_min"], self.wd.structure["params"]["plant_mass"], np.random.choice(self.wd.structure["params"]["crop_types"].split(",")), - i + i, ) for i, plant in enumerate(self.crop_placements) ] - + # place objects object_coordinates = [ into_dict( @@ -320,15 +321,16 @@ def into_dict(xy, ground_height, radius, height, mass, m_type, index): self.wd.structure["params"]["plant_radius"], self.wd.structure["params"]["plant_height_min"], self.wd.structure["params"]["plant_mass"], - "ghost_%s" % self.object_types[i] if self.wd.structure["params"] - ["ghost_objects"] else self.object_types[i], - i + "ghost_%s" % self.object_types[i] + if self.wd.structure["params"]["ghost_objects"] + else self.object_types[i], + i, ) for i, plant in enumerate(self.object_placements) ] coordinates.extend(object_coordinates) - + pkg_path = rospkg.RosPack().get_path("virtual_maize_field") template_path = os.path.join(pkg_path, "scripts/field.world.template") template = open(template_path).read() @@ -342,7 +344,6 @@ def into_dict(xy, ground_height, radius, height, mass, m_type, index): "x": self.heightmap_position[0], "y": self.heightmap_position[1], }, - "max_elevation": self.wd.structure["params"]["ground_max_elevation"], + "max_elevation": self.wd.structure["params"]["ground_elevation_max"], }, ) - diff --git a/virtual_maize_field/scripts/generate_world.py b/virtual_maize_field/scripts/generate_world.py index 171ddf8..e3050de 100755 --- a/virtual_maize_field/scripts/generate_world.py +++ b/virtual_maize_field/scripts/generate_world.py @@ -3,7 +3,10 @@ import rospkg import argparse import inspect + import os +import shutil + import cv2 from matplotlib import pyplot as plt @@ -46,7 +49,15 @@ pkg_path, "Media/models/virtual_maize_field_heightmap.png" ) cv2.imwrite(heightmap_path, fgen.heightmap) - + + # clear the gazbeo cache for old heightmap + home_dir = os.path.expanduser("~") + gazebo_cache_pkg = os.path.join( + home_dir, ".gazebo/paging/virtual_maize_field_heightmap" + ) + if os.path.isdir(gazebo_cache_pkg): + shutil.rmtree(gazebo_cache_pkg) + # save mini_map - mini_map_path = os.path.join(pkg_path, "virtual_maize_field_mini_map.png") - fgen.mini_map.savefig(mini_map_path, dpi=1000) + minimap_path = os.path.join(pkg_path, "generated_minimap.png") + fgen.minimap.savefig(minimap_path, dpi=1000) diff --git a/virtual_maize_field/scripts/row_segments.py b/virtual_maize_field/scripts/row_segments.py index 881f57f..c57c7d9 100644 --- a/virtual_maize_field/scripts/row_segments.py +++ b/virtual_maize_field/scripts/row_segments.py @@ -32,10 +32,7 @@ def placements(self, offset=None): if offset == None: offset = np.full( (len(self.start_p)), - -( - self.plant_params["plant_spacing_max"] - + self.plant_params["plant_spacing_min"] - ) + -(self.plant_params["plant_spacing_max"] + self.plant_params["plant_spacing_min"]) / 2, ) @@ -67,9 +64,7 @@ def racing_lines(self, spacing): @abstractmethod def racing_line(self, row_number, spacing): if row_number > len(self.start_p) - 1: - raise ValueError( - "There is no racing line " + row_number + "/" + len(self.start_p) - 1 - ) + raise ValueError("There is no racing line " + row_number + "/" + len(self.start_p) - 1) # Must be implemented by the child class to render the segment @abstractmethod @@ -139,9 +134,7 @@ def render(self): class CurvedSegment(BaseSegment): - def __init__( - self, start_p, start_dir, plant_params, radius, curve_dir, arc_measure - ): + def __init__(self, start_p, start_dir, plant_params, radius, curve_dir, arc_measure): super(CurvedSegment, self).__init__(start_p, start_dir, plant_params) self.radius = radius self.curve_dir = curve_dir @@ -171,9 +164,9 @@ def get_plant_row(self, row_number, offset): cur_placement = Geometry.rotate(start, self.center, c / r) placements = [cur_placement] - while ( - c < l - self.plant_params["plant_spacing_min"] or not self.curve_dir - ) and (c > l + self.plant_params["plant_spacing_min"] or self.curve_dir): + while (c < l - self.plant_params["plant_spacing_min"] or not self.curve_dir) and ( + c > l + self.plant_params["plant_spacing_min"] or self.curve_dir + ): step = rot * self.bounded_gaussian.get(0.0) cur_placement = Geometry.rotate(cur_placement, self.center, step / r) placements.append(cur_placement) @@ -247,9 +240,7 @@ def __init__( self.radius = radius self.island_model = island_model self.island_model_radius = island_model_radius - self.island_row_radius = ( - island_model_radius if island_model_radius > radius else radius - ) + self.island_row_radius = island_model_radius if island_model_radius > radius else radius self.island_row = island_row # start p vec @@ -272,27 +263,17 @@ def __init__( # check which is bigger and us it if d_l > d_r: self.angle = a_l - self.radius_left = d_l - np.linalg.norm( - self.start_p_left[0] - self.start_p_left[-1] - ) - self.radius_right = d_l - np.linalg.norm( - self.start_p_right[0] - self.start_p_right[-1] - ) + self.radius_left = d_l - np.linalg.norm(self.start_p_left[0] - self.start_p_left[-1]) + self.radius_right = d_l - np.linalg.norm(self.start_p_right[0] - self.start_p_right[-1]) self.length = 2 * d_l * np.tan(self.angle) else: self.angle = a_r - self.radius_left = d_r - np.linalg.norm( - self.start_p_left[0] - self.start_p_left[-1] - ) - self.radius_right = d_r - np.linalg.norm( - self.start_p_right[0] - self.start_p_right[-1] - ) + self.radius_left = d_r - np.linalg.norm(self.start_p_left[0] - self.start_p_left[-1]) + self.radius_right = d_r - np.linalg.norm(self.start_p_right[0] - self.start_p_right[-1]) self.length = 2 * d_r * np.tan(self.angle) # Island - self.center_island = ( - self.start_p[self.island_row] + self.start_dir * 0.5 * self.length - ) + self.center_island = self.start_p[self.island_row] + self.start_dir * 0.5 * self.length # Left self.entrence_left = CurvedSegment( @@ -308,9 +289,7 @@ def __init__( lp1, ld1, plant_params, self.island_row_radius, False, 2 * self.angle ) lp2, ld2 = self.middle_left.end() - self.exit_left = CurvedSegment( - lp2, ld2, plant_params, self.radius_left, True, self.angle - ) + self.exit_left = CurvedSegment(lp2, ld2, plant_params, self.radius_left, True, self.angle) # Right self.entrence_right = CurvedSegment( @@ -345,27 +324,17 @@ def get_plant_row(self, row_number, offset): p3, next_offset = self.exit_left.get_plant_row(row_number, off2) placements = np.vstack([p1, p2, p3]) elif row_number > self.island_row: - p1, off1 = self.entrence_right.get_plant_row( - row_number - self.island_row, offset - ) - p2, off2 = self.middle_right.get_plant_row( - row_number - self.island_row, off1 - ) - p3, next_offset = self.exit_right.get_plant_row( - row_number - self.island_row, off2 - ) + p1, off1 = self.entrence_right.get_plant_row(row_number - self.island_row, offset) + p2, off2 = self.middle_right.get_plant_row(row_number - self.island_row, off1) + p3, next_offset = self.exit_right.get_plant_row(row_number - self.island_row, off2) placements = np.vstack([p1, p2, p3]) else: pel, off1 = self.entrence_left.get_plant_row(row_number, offset) pml, off2 = self.middle_left.get_plant_row(row_number, off1) pxl, nol = self.exit_left.get_plant_row(row_number, off2) - per, off1 = self.entrence_right.get_plant_row( - row_number - self.island_row, offset - ) - pmr, off2 = self.middle_right.get_plant_row( - row_number - self.island_row, off1 - ) + per, off1 = self.entrence_right.get_plant_row(row_number - self.island_row, offset) + pmr, off2 = self.middle_right.get_plant_row(row_number - self.island_row, off1) pxr, nor = self.exit_right.get_plant_row(row_number - self.island_row, off2) placements = np.vstack([pel, per, pml, pmr, pxl, pxr]) @@ -401,4 +370,4 @@ def render(self): self.entrence_right.render() self.middle_right.render() - self.exit_right.render() \ No newline at end of file + self.exit_right.render() diff --git a/virtual_maize_field/scripts/world_description.py b/virtual_maize_field/scripts/world_description.py index 5b48483..fc261ca 100755 --- a/virtual_maize_field/scripts/world_description.py +++ b/virtual_maize_field/scripts/world_description.py @@ -14,7 +14,6 @@ AVAILABLE_SEGMENTS = ["straight", "curved", "island"] - class WorldDescription: def __init__( self, @@ -32,8 +31,8 @@ def __init__( row_segment_curved_arc_measure_max=1.0, row_segment_island_radius_min=1.0, row_segment_island_radius_max=3.0, - ground_max_elevation=0.2, - dem_res=0.10, + ground_resolution=0.02, + ground_elevation_max=0.2, plant_spacing_min=0.13, plant_spacing_max=0.19, plant_height_min=0.3, @@ -42,8 +41,8 @@ def __init__( plant_radius_noise=0.05, plant_placement_error_max=0.02, plant_mass=0.3, - hole_prob = 0.0, - max_hole_size = 7, + hole_prob=0.0, + hole_size_max=7, crop_types=",".join(AVAILABLE_CROP_TYPES[1:]), litters=0, litter_types=",".join(AVAILABLE_LITTER_TYPES), @@ -51,7 +50,7 @@ def __init__( weed_types=",".join(AVAILABLE_WEED_TYPES), ghost_objects=False, load_from_file=None, - seed=-1 + seed=-1, ): row_segments = row_segments.split(",") @@ -72,8 +71,8 @@ def __init__( def random_description(self): self.structure = dict() self.structure["params"] = { - "ground_max_elevation": self.ground_max_elevation, - "dem_res": self.dem_res, + "ground_resolution": self.ground_resolution, + "ground_elevation_max": self.ground_elevation_max, "plant_spacing_min": self.plant_spacing_min, "plant_spacing_max": self.plant_spacing_max, "plant_height_min": self.plant_height_min, @@ -83,13 +82,13 @@ def random_description(self): "plant_placement_error_max": self.plant_placement_error_max, "plant_mass": self.plant_mass, "hole_prob": self.hole_prob, - "max_hole_size": self.max_hole_size, + "hole_size_max": self.hole_size_max, "crop_types": self.crop_types, "litter_types": self.litter_types, - "litters":self.litters, + "litters": self.litters, "weed_types": self.weed_types, - "weeds" :self.weeds, - "ghost_objects":self.ghost_objects, + "weeds": self.weeds, + "ghost_objects": self.ghost_objects, "seed": self.seed, } @@ -104,10 +103,7 @@ def random_description(self): if segment_name == "straight": length = ( np.random.rand() - * ( - self.row_segment_straight_length_max - - self.row_segment_straight_length_min - ) + * (self.row_segment_straight_length_max - self.row_segment_straight_length_min) + self.row_segment_straight_length_min ) @@ -118,10 +114,7 @@ def random_description(self): elif segment_name == "curved": radius = ( np.random.rand() - * ( - self.row_segment_curved_radius_max - - self.row_segment_curved_radius_min - ) + * (self.row_segment_curved_radius_max - self.row_segment_curved_radius_min) + self.row_segment_curved_radius_min ) arc_measure = ( @@ -146,19 +139,14 @@ def random_description(self): } current_row_length += ( - arc_measure - * ((self.rows_left + self.rows_right) * self.row_width + radius) - / 2 + arc_measure * ((self.rows_left + self.rows_right) * self.row_width + radius) / 2 ) current_curve = arc_measure if not curve_dir else -arc_measure elif segment_name == "island": radius = ( np.random.rand() - * ( - self.row_segment_island_radius_max - - self.row_segment_island_radius_min - ) + * (self.row_segment_island_radius_max - self.row_segment_island_radius_min) + self.row_segment_island_radius_min ) island_row = np.random.randint(self.rows_left + self.rows_right - 1) + 1 @@ -213,4 +201,4 @@ def save(self, path): args = {k: v for k, v in args.items() if v is not None} pk = WorldDescription(**args) - print(pk) \ No newline at end of file + print(pk) diff --git a/virtual_maize_field/virtual_maize_field_mini_map.png b/virtual_maize_field/virtual_maize_field_mini_map.png new file mode 100644 index 0000000..1447175 Binary files /dev/null and b/virtual_maize_field/virtual_maize_field_mini_map.png differ