Skip to content

Commit 499a609

Browse files
committed
version bump and formatting
1 parent 14005bb commit 499a609

File tree

18 files changed

+64
-36
lines changed

18 files changed

+64
-36
lines changed

examples/policy.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,8 @@
3838

3939
import numpy as np
4040

41-
from autolab_core import YamlConfig, Logger, BinaryImage, CameraIntrinsics, ColorImage, DepthImage, RgbdImage
41+
from autolab_core import (YamlConfig, Logger, BinaryImage, CameraIntrinsics,
42+
ColorImage, DepthImage, RgbdImage)
4243
from visualization import Visualizer2D as vis
4344

4445
from gqcnn.grasping import (RobustGraspingPolicy,

examples/policy_ros.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,8 @@
3939

4040
from cv_bridge import CvBridge, CvBridgeError
4141

42-
from autolab_core import Point, Logger, BinaryImage, CameraIntrinsics, ColorImage, DepthImage
42+
from autolab_core import (Point, Logger, BinaryImage, CameraIntrinsics,
43+
ColorImage, DepthImage)
4344
from visualization import Visualizer2D as vis
4445

4546
from gqcnn.grasping import Grasp2D, SuctionPoint2D, GraspAction

examples/policy_with_image_proc.py

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,10 @@
3737
import pcl
3838
import skimage
3939

40-
from autolab_core import PointCloud, RigidTransform, YamlConfig, Logger, BinaryImage, CameraIntrinsics, ColorImage, DepthImage, RgbdImage, SegmentationImage
40+
from autolab_core import (PointCloud, RigidTransform, YamlConfig,
41+
Logger, BinaryImage, CameraIntrinsics,
42+
ColorImage, DepthImage, RgbdImage,
43+
SegmentationImage)
4144
from visualization import Visualizer2D as vis
4245

4346
from gqcnn import (RobustGraspingPolicy, CrossEntropyRobustGraspingPolicy,

gqcnn/analysis/analyzer.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,8 @@
3535
import matplotlib.pyplot as plt
3636
import numpy as np
3737

38-
from autolab_core import BinaryClassificationResult, TensorDataset, Logger, DepthImage
38+
from autolab_core import (BinaryClassificationResult, TensorDataset,
39+
Logger, DepthImage)
3940
from autolab_core.constants import JSON_INDENT
4041
import autolab_core.utils as utils
4142
from visualization import Visualizer2D as vis2d

gqcnn/grasping/constraint_fn.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -117,6 +117,7 @@ def satisfies_constraints(self, grasp):
117117

118118

119119
class GraspConstraintFnFactory(object):
120+
120121
@staticmethod
121122
def constraint_fn(fn_type, config):
122123
if fn_type == "none":

gqcnn/grasping/grasp_quality_function.py

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -816,6 +816,7 @@ def quality(self, state, actions, params=None):
816816

817817
class DiscCurvatureSuctionQualityFunction(
818818
GaussianCurvatureSuctionQualityFunction):
819+
819820
def __init__(self, config):
820821
"""Create approach planarity suction metric."""
821822
self._radius = config["radius"]
@@ -848,6 +849,7 @@ def _points_in_window(self, point_cloud_image, action, segmask=None):
848849

849850
class ComDiscCurvatureSuctionQualityFunction(
850851
DiscCurvatureSuctionQualityFunction):
852+
851853
def __init__(self, config):
852854
"""Create approach planarity suction metric."""
853855
self._curvature_pctile = config["curvature_pctile"]
@@ -911,6 +913,7 @@ def quality(self, state, actions, params=None):
911913

912914

913915
class GQCnnQualityFunction(GraspQualityFunction):
916+
914917
def __init__(self, config):
915918
"""Create a GQCNN suction quality function."""
916919
GraspQualityFunction.__init__(self)
@@ -1067,6 +1070,7 @@ def quality(self, state, actions, params):
10671070

10681071

10691072
class NoMagicQualityFunction(GraspQualityFunction):
1073+
10701074
def __init__(self, config):
10711075
"""Create a quality that uses `nomagic_net` as a quality function."""
10721076
from nomagic_submission import ConvNetModel
@@ -1154,8 +1158,8 @@ def grasps_to_tensors(self, grasps, state):
11541158
255))[1].tostring()
11551159
im_decoded = cv2.imdecode(np.frombuffer(im_encoded, np.uint8),
11561160
0) / 255.0
1157-
image_tensor[i, :, :, 0] = ((im_decoded - self._data_mean) /
1158-
self._data_std)
1161+
image_tensor[i, :, :,
1162+
0] = ((im_decoded - self._data_mean) / self._data_std)
11591163

11601164
if gripper_mode == GripperMode.PARALLEL_JAW:
11611165
pose_tensor[i] = grasp.depth
@@ -1230,6 +1234,7 @@ def quality(self, state, actions, params):
12301234

12311235

12321236
class FCGQCnnQualityFunction(GraspQualityFunction):
1237+
12331238
def __init__(self, config):
12341239
"""Grasp quality function using the fully-convolutional gqcnn."""
12351240
GraspQualityFunction.__init__(self)

gqcnn/grasping/image_grasp_sampler.py

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,8 @@
3939
import scipy.spatial.distance as ssd
4040
import scipy.stats as ss
4141

42-
from autolab_core import Point, RigidTransform, Logger, DepthImage, RgbdImage, GdImage
42+
from autolab_core import (Point, RigidTransform, Logger,
43+
DepthImage, RgbdImage, GdImage)
4344
from visualization import Visualizer2D as vis
4445

4546
from .grasp import Grasp2D, SuctionPoint2D, MultiSuctionPoint2D
@@ -558,8 +559,8 @@ def _sample_antipodal_grasps(self,
558559
for i in range(self._depth_samples_per_grasp):
559560
# Get depth in the neighborhood of the center pixel.
560561
depth_win = depth_im.data[grasp_center[0] -
561-
self._h:grasp_center[0] +
562-
self._h, grasp_center[1] -
562+
self._h:grasp_center[0] + self._h,
563+
grasp_center[1] -
563564
self._w:grasp_center[1] + self._w]
564565
center_depth = np.min(depth_win)
565566
if center_depth == 0 or np.isnan(center_depth):

gqcnn/grasping/policy/fc_policy.py

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -105,8 +105,8 @@ def _mask_predictions(self, preds, raw_segmask):
105105
preds_masked = np.zeros_like(preds)
106106
raw_segmask_cropped = raw_segmask[self._gqcnn_recep_h //
107107
2:raw_segmask.shape[0] -
108-
self._gqcnn_recep_h //
109-
2, self._gqcnn_recep_w //
108+
self._gqcnn_recep_h // 2,
109+
self._gqcnn_recep_w //
110110
2:raw_segmask.shape[1] -
111111
self._gqcnn_recep_w // 2, 0]
112112
raw_segmask_downsampled = raw_segmask_cropped[::self._gqcnn_stride, ::
@@ -321,8 +321,8 @@ def _action(self, state, num_actions=1):
321321
self._vis_scale,
322322
output_dir=state_output_dir)
323323

324-
return actions[-1] if (self._filter_grasps or num_actions == 1
325-
) else actions[-(num_actions + 1):]
324+
return actions[-1] if (self._filter_grasps or num_actions
325+
== 1) else actions[-(num_actions + 1):]
326326

327327
def action_set(self, state, num_actions):
328328
"""Plan a set of actions.
@@ -411,8 +411,8 @@ def _get_actions(self, preds, ind, images, depths, camera_intr,
411411
depth,
412412
width=self._gripper_width,
413413
camera_intr=camera_intr)
414-
grasp_action = GraspAction(grasp,
415-
preds[im_idx, h_idx, w_idx, ang_idx],
414+
grasp_action = GraspAction(grasp, preds[im_idx, h_idx, w_idx,
415+
ang_idx],
416416
DepthImage(images[im_idx]))
417417
actions.append(grasp_action)
418418
return actions

gqcnn/grasping/policy/policy.py

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,9 @@
4242
from sklearn.mixture import GaussianMixture
4343

4444
import autolab_core.utils as utils
45-
from autolab_core import Point, Logger, BinaryImage, ColorImage, DepthImage, RgbdImage, SegmentationImage, CameraIntrinsics
45+
from autolab_core import (Point, Logger, BinaryImage, ColorImage,
46+
DepthImage, RgbdImage, SegmentationImage,
47+
CameraIntrinsics)
4648
from visualization import Visualizer2D as vis
4749

4850
from ..constraint_fn import GraspConstraintFnFactory
@@ -1238,7 +1240,7 @@ def action_set(self, state):
12381240
q_values=norm_q_values,
12391241
scale=2.0,
12401242
title=title,
1241-
save_fname="final_sampled_grasps.png".format(j),
1243+
save_fname="final_sampled_grasps.png",
12421244
save_path=state_output_dir)
12431245
display_grasps_and_q_values = zip(grasps, q_values)
12441246
display_grasps_and_q_values = sorted(display_grasps_and_q_values,
@@ -1545,6 +1547,7 @@ def set_constraint_fn(self, constraint_fn):
15451547

15461548

15471549
class PriorityCompositeGraspingPolicy(CompositeGraspingPolicy):
1550+
15481551
def __init__(self, policies, priority_list):
15491552
# Check validity.
15501553
for name in priority_list:
@@ -1613,6 +1616,7 @@ def action_set(self, state, policy_subset=None, min_q_value=-1.0):
16131616

16141617

16151618
class GreedyCompositeGraspingPolicy(CompositeGraspingPolicy):
1619+
16161620
def __init__(self, policies):
16171621
CompositeGraspingPolicy.__init__(self, policies)
16181622

gqcnn/model/tf/network_tf.py

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -878,21 +878,21 @@ def _predict(self, image_arr, pose_arr, verbose=False):
878878
end_ind = cur_ind + dim
879879

880880
if self._input_depth_mode == InputDepthMode.POSE_STREAM:
881-
self._input_im_arr[:dim, ...] = (
882-
image_arr[cur_ind:end_ind, ...] -
883-
self._im_mean) / self._im_std
881+
self._input_im_arr[:dim,
882+
...] = (image_arr[cur_ind:end_ind, ...]
883+
- self._im_mean) / self._im_std
884884
self._input_pose_arr[:dim, :] = (
885885
pose_arr[cur_ind:end_ind, :] -
886886
self._pose_mean) / self._pose_std
887887
elif self._input_depth_mode == InputDepthMode.SUB:
888888
self._input_im_arr[:dim, ...] = image_arr[cur_ind:end_ind,
889889
...]
890-
self._input_pose_arr[:dim, :] = pose_arr[cur_ind:
891-
end_ind, :]
890+
self._input_pose_arr[:dim, :] = pose_arr[
891+
cur_ind:end_ind, :]
892892
elif self._input_depth_mode == InputDepthMode.IM_ONLY:
893-
self._input_im_arr[:dim, ...] = (
894-
image_arr[cur_ind:end_ind, ...] -
895-
self._im_mean) / self._im_std
893+
self._input_im_arr[:dim,
894+
...] = (image_arr[cur_ind:end_ind, ...]
895+
- self._im_mean) / self._im_std
896896

897897
gqcnn_output = self._sess.run(
898898
self._output_tensor,
@@ -1417,9 +1417,9 @@ def _build_network(self, input_im_node, input_pose_node,
14171417
self._input_depth_mode == InputDepthMode.IM_ONLY:
14181418
extraneous_stream_msg = ("When using input depth mode '{}', only"
14191419
" im stream is allowed!")
1420-
assert not ("pose_stream" in self._architecture
1421-
or "merge_stream" in self._architecture
1422-
), extraneous_stream_msg.format(self._input_depth_mode)
1420+
assert not ("pose_stream" in self._architecture or "merge_stream"
1421+
in self._architecture), extraneous_stream_msg.format(
1422+
self._input_depth_mode)
14231423
with tf.name_scope("im_stream"):
14241424
return self._build_im_stream(input_im_node,
14251425
input_pose_node,

0 commit comments

Comments
 (0)