Skip to content

Commit

Permalink
Applied black formatting.
Browse files Browse the repository at this point in the history
  • Loading branch information
mktk1117 committed Dec 6, 2023
1 parent 330a1de commit 9742a25
Show file tree
Hide file tree
Showing 34 changed files with 166 additions and 473 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -228,10 +228,7 @@ def shift_map_z(self, delta_z):
def compile_kernels(self):
"""Compile all kernels belonging to the elevation map."""

self.new_map = cp.zeros(
(self.elevation_map.shape[0], self.cell_n, self.cell_n),
dtype=self.data_type,
)
self.new_map = cp.zeros((self.elevation_map.shape[0], self.cell_n, self.cell_n), dtype=self.data_type,)
self.traversability_input = cp.zeros((self.cell_n, self.cell_n), dtype=self.data_type)
self.traversability_mask_dummy = cp.zeros((self.cell_n, self.cell_n), dtype=self.data_type)
self.min_filtered = cp.zeros((self.cell_n, self.cell_n), dtype=self.data_type)
Expand Down Expand Up @@ -290,18 +287,14 @@ def compile_image_kernels(self):
np.zeros((self.cell_n, self.cell_n), dtype=np.bool_), dtype=np.bool_
)
self.uv_correspondence = cp.asarray(
np.zeros((2, self.cell_n, self.cell_n), dtype=np.float32),
dtype=np.float32,
np.zeros((2, self.cell_n, self.cell_n), dtype=np.float32), dtype=np.float32,
)
# self.distance_correspondence = cp.asarray(
# np.zeros((self.cell_n, self.cell_n), dtype=np.float32), dtype=np.float32
# )
# TODO tolerance_z_collision add parameter
self.image_to_map_correspondence_kernel = image_to_map_correspondence_kernel(
resolution=self.resolution,
width=self.cell_n,
height=self.cell_n,
tolerance_z_collision=0.10,
resolution=self.resolution, width=self.cell_n, height=self.cell_n, tolerance_z_collision=0.10,
)
break

Expand Down Expand Up @@ -529,12 +522,7 @@ def input_image(
size=int(self.cell_n * self.cell_n),
)
self.semantic_map.update_layers_image(
image,
channels,
self.uv_correspondence,
self.valid_correspondence,
image_height,
image_width,
image, channels, self.uv_correspondence, self.valid_correspondence, image_height, image_width,
)

def update_normal(self, dilated_map):
Expand All @@ -546,10 +534,7 @@ def update_normal(self, dilated_map):
with self.map_lock:
self.normal_map *= 0.0
self.normal_filter_kernel(
dilated_map,
self.elevation_map[2],
self.normal_map,
size=(self.cell_n * self.cell_n),
dilated_map, self.elevation_map[2], self.normal_map, size=(self.cell_n * self.cell_n),
)

def process_map_for_publish(self, input_map, fill_nan=False, add_z=False, xp=cp):
Expand Down Expand Up @@ -595,9 +580,7 @@ def get_traversability(self):
traversability layer
"""
traversability = cp.where(
(self.elevation_map[2] + self.elevation_map[6]) > 0.5,
self.elevation_map[3].copy(),
cp.nan,
(self.elevation_map[2] + self.elevation_map[6]) > 0.5, self.elevation_map[3].copy(), cp.nan,
)
self.traversability_buffer[3:-3, 3:-3] = traversability[3:-3, 3:-3]
traversability = self.traversability_buffer[1:-1, 1:-1]
Expand All @@ -619,8 +602,7 @@ def get_upper_bound(self):
"""
if self.param.use_only_above_for_upper_bound:
valid = cp.logical_or(
cp.logical_and(self.elevation_map[5] > 0.0, self.elevation_map[6] > 0.5),
self.elevation_map[2] > 0.5,
cp.logical_and(self.elevation_map[5] > 0.0, self.elevation_map[6] > 0.5), self.elevation_map[2] > 0.5,
)
else:
valid = cp.logical_or(self.elevation_map[2] > 0.5, self.elevation_map[6] > 0.5)
Expand All @@ -636,8 +618,7 @@ def get_is_upper_bound(self):
"""
if self.param.use_only_above_for_upper_bound:
valid = cp.logical_or(
cp.logical_and(self.elevation_map[5] > 0.0, self.elevation_map[6] > 0.5),
self.elevation_map[2] > 0.5,
cp.logical_and(self.elevation_map[5] > 0.0, self.elevation_map[6] > 0.5), self.elevation_map[2] > 0.5,
)
else:
valid = cp.logical_or(self.elevation_map[2] > 0.5, self.elevation_map[6] > 0.5)
Expand Down Expand Up @@ -798,11 +779,7 @@ def get_layer(self, name):
return_map = self.semantic_map.semantic_map[idx]
elif name in self.plugin_manager.layer_names:
self.plugin_manager.update_with_name(
name,
self.elevation_map,
self.layer_names,
self.semantic_map,
self.base_rotation,
name, self.elevation_map, self.layer_names, self.semantic_map, self.base_rotation,
)
return_map = self.plugin_manager.get_map_with_name(name)
else:
Expand Down Expand Up @@ -848,10 +825,7 @@ def get_polygon_traversability(self, polygon, result):
else:
t = cp.asarray(0.0, dtype=self.data_type)
is_safe, un_polygon = is_traversable(
masked,
self.param.safe_thresh,
self.param.safe_min_thresh,
self.param.max_unsafe_n,
masked, self.param.safe_thresh, self.param.safe_min_thresh, self.param.max_unsafe_n,
)
untraversable_polygon_num = 0
if un_polygon is not None:
Expand Down Expand Up @@ -907,9 +881,7 @@ def initialize_map(self, points, method="cubic"):
t = xp.random.rand(3)
print(R, t)
param = Parameter(
use_chainer=False,
weight_file="../config/weights.dat",
plugin_config_file="../config/plugin_config.yaml",
use_chainer=False, weight_file="../config/weights.dat", plugin_config_file="../config/plugin_config.yaml",
)
param.additional_layers = ["rgb", "grass", "tree", "people"]
param.fusion_algorithms = ["color", "class_bayesian", "class_bayesian", "class_bayesian"]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,9 +53,7 @@ def __init__(self, params, *args, **kwargs):
self.resolution = params.resolution

self.color_correspondences_to_map_kernel = color_correspondences_to_map_kernel(
resolution=self.resolution,
width=self.cell_n,
height=self.cell_n,
resolution=self.resolution, width=self.cell_n, height=self.cell_n,
)

def __call__(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,10 +44,7 @@ def __init__(self, params, *args, **kwargs):
self.resolution = params.resolution

self.exponential_correspondences_to_map_kernel = exponential_correspondences_to_map_kernel(
resolution=self.resolution,
width=self.cell_n,
height=self.cell_n,
alpha=0.7,
resolution=self.resolution, width=self.cell_n, height=self.cell_n, alpha=0.7,
)

def __call__(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,7 @@


def sum_kernel(
resolution,
width,
height,
resolution, width, height,
):
"""Sums the semantic values of the classes for the exponentiala verage or for the average.
Expand Down Expand Up @@ -53,8 +51,7 @@ def sum_kernel(


def average_kernel(
width,
height,
width, height,
):
average_kernel = cp.ElementwiseKernel(
in_params="raw V newmap, raw W pcl_chan, raw W map_lay, raw W pcl_channels, raw U new_elmap",
Expand Down Expand Up @@ -90,15 +87,8 @@ def __init__(self, params, *args, **kwargs):
self.name = "pointcloud_average"
self.cell_n = params.cell_n
self.resolution = params.resolution
self.sum_kernel = sum_kernel(
self.resolution,
self.cell_n,
self.cell_n,
)
self.average_kernel = average_kernel(
self.cell_n,
self.cell_n,
)
self.sum_kernel = sum_kernel(self.resolution, self.cell_n, self.cell_n,)
self.average_kernel = average_kernel(self.cell_n, self.cell_n,)

def __call__(self, points_all, R, t, pcl_ids, layer_ids, elevation_map, semantic_map, new_map, *args):
self.sum_kernel(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,7 @@


def sum_compact_kernel(
resolution,
width,
height,
resolution, width, height,
):
# input the list of layers, amount of channels can slo be input through kernel
sum_compact_kernel = cp.ElementwiseKernel(
Expand Down Expand Up @@ -43,8 +41,7 @@ def sum_compact_kernel(


def bayesian_inference_kernel(
width,
height,
width, height,
):
bayesian_inference_kernel = cp.ElementwiseKernel(
in_params=" raw W pcl_chan, raw W map_lay, raw W pcl_channels, raw U new_elmap",
Expand Down Expand Up @@ -91,23 +88,11 @@ def __init__(self, params, *args, **kwargs):
self.data_type = params.data_type

self.sum_mean = cp.ones(
(
self.fusion_algorithms.count("bayesian_inference"),
self.cell_n,
self.cell_n,
),
self.data_type,
(self.fusion_algorithms.count("bayesian_inference"), self.cell_n, self.cell_n,), self.data_type,
)
# TODO initialize the variance with a value different than 0
self.sum_compact_kernel = sum_compact_kernel(
self.resolution,
self.cell_n,
self.cell_n,
)
self.bayesian_inference_kernel = bayesian_inference_kernel(
self.cell_n,
self.cell_n,
)
self.sum_compact_kernel = sum_compact_kernel(self.resolution, self.cell_n, self.cell_n,)
self.bayesian_inference_kernel = bayesian_inference_kernel(self.cell_n, self.cell_n,)

def __call__(self, points_all, R, t, pcl_ids, layer_ids, elevation_map, semantic_map, new_map, *args):
self.sum_mean *= 0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,7 @@


def sum_kernel(
resolution,
width,
height,
resolution, width, height,
):
"""Sums the semantic values of the classes for the exponentiala verage or for the average.
Expand Down Expand Up @@ -53,9 +51,7 @@ def sum_kernel(


def class_average_kernel(
width,
height,
alpha,
width, height, alpha,
):
class_average_kernel = cp.ElementwiseKernel(
in_params="raw V newmap, raw W pcl_chan, raw W map_lay, raw W pcl_channels, raw U new_elmap",
Expand Down Expand Up @@ -85,9 +81,7 @@ def class_average_kernel(
}
}
"""
).substitute(
alpha=alpha,
),
).substitute(alpha=alpha,),
name="class_average_kernel",
)
return class_average_kernel
Expand All @@ -102,16 +96,8 @@ def __init__(self, params, *args, **kwargs):
self.resolution = params.resolution
self.average_weight = params.average_weight

self.sum_kernel = sum_kernel(
self.resolution,
self.cell_n,
self.cell_n,
)
self.class_average_kernel = class_average_kernel(
self.cell_n,
self.cell_n,
self.average_weight,
)
self.sum_kernel = sum_kernel(self.resolution, self.cell_n, self.cell_n,)
self.class_average_kernel = class_average_kernel(self.cell_n, self.cell_n, self.average_weight,)

def __call__(self, points_all, R, t, pcl_ids, layer_ids, elevation_map, semantic_map, new_map, *args):
self.sum_kernel(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,7 @@


def alpha_kernel(
resolution,
width,
height,
resolution, width, height,
):
# input the list of layers, amount of channels can slo be input through kernel
alpha_kernel = cp.ElementwiseKernel(
Expand Down Expand Up @@ -55,11 +53,7 @@ def __init__(self, params, *args, **kwargs):
self.name = "pointcloud_class_bayesian"
self.cell_n = params.cell_n
self.resolution = params.resolution
self.alpha_kernel = alpha_kernel(
self.resolution,
self.cell_n,
self.cell_n,
)
self.alpha_kernel = alpha_kernel(self.resolution, self.cell_n, self.cell_n,)

def __call__(self, points_all, R, t, pcl_ids, layer_ids, elevation_map, semantic_map, new_map, *args):
self.alpha_kernel(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,7 @@


def sum_max_kernel(
resolution,
width,
height,
resolution, width, height,
):
# input the list of layers, amount of channels can slo be input through kernel
sum_max_kernel = cp.ElementwiseKernel(
Expand Down Expand Up @@ -53,11 +51,7 @@ def __init__(self, params, *args, **kwargs):
self.resolution = params.resolution
self.fusion_algorithms = params.fusion_algorithms

self.sum_max_kernel = sum_max_kernel(
self.resolution,
self.cell_n,
self.cell_n,
)
self.sum_max_kernel = sum_max_kernel(self.resolution, self.cell_n, self.cell_n,)
layer_cnt = self.fusion_algorithms.count("class_max")

self.unique_id = cp.array([0])
Expand Down Expand Up @@ -88,10 +82,7 @@ def __call__(self, points_all, R, t, pcl_ids, layer_ids, elevation_map, semantic
# get all unique ids, where index is the position in the prob_sum and the value in the NN class
self.unique_id = cp.unique(cp.concatenate((unique_idm, unique_ida)))
# contains the sum of the new measurement probabilities
self.prob_sum = cp.zeros(
(len(self.unique_id), self.cell_n, self.cell_n),
dtype=np.float32,
)
self.prob_sum = cp.zeros((len(self.unique_id), self.cell_n, self.cell_n), dtype=np.float32,)
# transform the index matrix of the classes to the index matrix of the prob_sum
pt_id_zero = pt_id.copy()
for it, val in enumerate(self.unique_id):
Expand All @@ -104,10 +95,7 @@ def __call__(self, points_all, R, t, pcl_ids, layer_ids, elevation_map, semantic
pt_id_zero,
pcl_ids,
layer_ids,
cp.array(
[points_all.shape[1], pcl_ids.shape[0], pt_id.shape[1]],
dtype=cp.int32,
),
cp.array([points_all.shape[1], pcl_ids.shape[0], pt_id.shape[1]], dtype=cp.int32,),
self.prob_sum,
size=(points_all.shape[0]),
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,7 @@


def add_color_kernel(
width,
height,
width, height,
):
add_color_kernel = cp.ElementwiseKernel(
in_params="raw T p, raw U R, raw U t, raw W pcl_chan, raw W map_lay, raw W pcl_channels",
Expand Down Expand Up @@ -57,8 +56,7 @@ def add_color_kernel(


def color_average_kernel(
width,
height,
width, height,
):
color_average_kernel = cp.ElementwiseKernel(
in_params="raw V color_map, raw W pcl_chan, raw W map_lay, raw W pcl_channels",
Expand Down Expand Up @@ -123,17 +121,11 @@ def __init__(self, params, *args, **kwargs):
self.cell_n = params.cell_n
self.resolution = params.resolution

self.add_color_kernel = add_color_kernel(
params.cell_n,
params.cell_n,
)
self.add_color_kernel = add_color_kernel(params.cell_n, params.cell_n,)
self.color_average_kernel = color_average_kernel(self.cell_n, self.cell_n)

def __call__(self, points_all, R, t, pcl_ids, layer_ids, elevation_map, semantic_map, new_map, *args):
self.color_map = cp.zeros(
(1 + 3 * layer_ids.shape[0], self.cell_n, self.cell_n),
dtype=cp.uint32,
)
self.color_map = cp.zeros((1 + 3 * layer_ids.shape[0], self.cell_n, self.cell_n), dtype=cp.uint32,)

points_all = points_all.astype(cp.float32)
self.add_color_kernel(
Expand Down
Loading

0 comments on commit 9742a25

Please sign in to comment.