Skip to content

Commit

Permalink
fix for python3, use 2to3 -f print, 2to3 -f except
Browse files Browse the repository at this point in the history
  • Loading branch information
k-okada committed Aug 26, 2020
1 parent fad6083 commit 313060f
Show file tree
Hide file tree
Showing 25 changed files with 109 additions and 109 deletions.
2 changes: 1 addition & 1 deletion checkerboard_detector/src/objectdetection_tf_publisher.py
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ def send_dynamic_tf_request(self, pos_x, pos_y, pos_z, ori_x, ori_y, ori_z, ori_
try:
res = set_dynamic_tf(set_tf_request)
except rospy.ServiceException as exc:
print("Service did not process request: " + str(exc))
print(("Service did not process request: " + str(exc)))

if __name__== '__main__':
rospy.init_node('objectdetection_tf_publisher', anonymous=True)
Expand Down
8 changes: 4 additions & 4 deletions cr_calibration/cr_calibration.py
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ def queue_cr(self, limg, linfo, rimg, rinfo):
return False

dist = self.calc_distance(self.static_pose, lframe)
print dist
print(dist)
if dist > 0.012:
self.frame_list = []
self.static_pose = None
Expand All @@ -116,8 +116,8 @@ def queue_cr(self, limg, linfo, rimg, rinfo):
# finish check
if len(self.result_list) > 7 and self.last_err < 0.1:
rospy.loginfo("Finished size = %d, err = %f" % (len(self.result_list), self.last_err))
print "translation: [%f, %f, %f]\nrotation: [%f, %f, %f, %f]" % (ret.p.x(), ret.p.y(), ret.p.z(), qx, qy, qz, qw)
print "(make-coords :pos #f(%f %f %f) :rot (quaternion2matrix #f(%f %f %f %f)))" % (1000*ret.p.x(), 1000*ret.p.y(), 1000*ret.p.z(), qw, qx, qy, qz)
print("translation: [%f, %f, %f]\nrotation: [%f, %f, %f, %f]" % (ret.p.x(), ret.p.y(), ret.p.z(), qx, qy, qz, qw))
print("(make-coords :pos #f(%f %f %f) :rot (quaternion2matrix #f(%f %f %f %f)))" % (1000*ret.p.x(), 1000*ret.p.y(), 1000*ret.p.z(), qw, qx, qy, qz))
#print "<node pkg=\"tf\" type=\"static_transform_publisher\" name=\"cam_link_broadcaster\" args=\"%f %f %f %f %f %f %f link1 link2 30\" />" % (ret.p.x(), ret.p.y(), ret.p.z(), qw, qx, qy, qz)
exit(-1)

Expand Down Expand Up @@ -195,7 +195,7 @@ def find_checkerboard_pose(self, ros_image, cam_info):
#we need to convert the ros image to an opencv image
try:
image = self.bridge.imgmsg_to_cv(ros_image, "mono8")
except CvBridgeError, e:
except CvBridgeError as e:
rospy.logerror("Error importing image %s" % e)
return

Expand Down
2 changes: 1 addition & 1 deletion doc/conf.py
Original file line number Diff line number Diff line change
Expand Up @@ -179,7 +179,7 @@

# Additional stuff for the LaTeX preamble.
'preamble': "".join((
'\usepackage[utf8]{inputenc}',
"\\usepackage[utf8]{inputenc}",
# NO-BREAK SPACE
'\DeclareUnicodeCharacter{00A0}{ }',
# BOX DRAWINGS LIGHT VERTICAL AND RIGHT
Expand Down
24 changes: 12 additions & 12 deletions jsk_pcl_ros/scripts/check_depth_error/depth_error_calibration.py
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,7 @@ def setParameter(classifier):
c0 = classifier.intercept_
param = DepthCalibrationParameter()
if not isValidClassifier(classifier):
print "parameters are list"
print("parameters are list")
return
if model == "linear":
param.coefficients2 = [0, 0, 0, 0, 0]
Expand Down Expand Up @@ -168,7 +168,7 @@ def processData(x, y, u, v, cu, cv, fit = True):
zs = value_cache[(uu, vv)]
for z in zs:
if abs(z - y) < eps_z:
print "duplicated value"
print("duplicated value")
return
else:
value_cache[(uu, vv)].append(y)
Expand All @@ -180,22 +180,22 @@ def processData(x, y, u, v, cu, cv, fit = True):
c_us.append(cu)
c_vs.append(cv)
if u > u_min and u < u_max and v < v_max and v > v_min:
print (x, y)
print((x, y))
xs.append(genFeatureVector(x, u, v, cu, cv))
ys.append(y)
if fit:
classifier.fit(xs, ys)
try:
setParameter(classifier)
except rospy.service.ServiceException, e:
except rospy.service.ServiceException as e:
rospy.logfatal("failed to call service: %s" % (e.message))
try:
print modelEquationString(classifier)
except Exception, e:
print(modelEquationString(classifier))
except Exception as e:
rospy.logwarn("failed to print model: %s" % e.message)

else:
print "(%d, %d) is out of range" % (u, v)
print("(%d, %d) is out of range" % (u, v))

def callback(msg):
global xs, ys, classifier, u_min, u_max, v_min, v_max, raw_xs
Expand Down Expand Up @@ -338,7 +338,7 @@ def updatePlot():
plot_img.shape = (h, w, 3)
plt.close()
pub_error_plot.publish(bridge.cv2_to_imgmsg(plot_img, "bgr8"))
except Exception, e:
except Exception as e:
rospy.logerr(e.message)

def generateFrequencyMap():
Expand Down Expand Up @@ -379,7 +379,7 @@ def main():
height = args.height
if args.models:
for m in MODELS:
print m
print(m)
return
model = args.model
if model not in MODELS:
Expand Down Expand Up @@ -409,22 +409,22 @@ def main():
classifier.fit(xs, ys)
try:
setParameter(classifier)
except rospy.service.ServiceException, e:
except rospy.service.ServiceException as e:
rospy.logfatal("failed to call service: %s" % (e.message))
try:
plt.show()
finally:
if not args.csv:
csv_filename = "calibration-%s.csv" % datetime.datetime.now().strftime('%Y-%m-%d-%H-%M-%S')
print "Save calibration parameters to %s" % (csv_filename)
print("Save calibration parameters to %s" % (csv_filename))
with open(csv_filename, "w") as f:
for x, y, u, v, cu, cv in zip(raw_xs, ys, us, vs, c_us, c_vs):
f.write("%f,%f,%d,%d,%f,%f\n" % (x, y, u, v, cu, cv))
dump = rospy.get_param("~dump_result_into_yaml", "query")
if dump is True or \
(dump == "query" and query_yes_no("Dump result into yaml file?")):
yaml_filename = "calibration_parameter_%s.yaml" % datetime.datetime.now().strftime('%Y_%m_%d_%H_%M_%S')
print "writing to %s" % yaml_filename
print("writing to %s" % yaml_filename)
c = classifier.coef_
if model == "quadratic-uv-abs" or model == "quadratic-uv-quadratic-abs":
use_abs = "True"
Expand Down
2 changes: 1 addition & 1 deletion jsk_pcl_ros/scripts/draw_3d_circle.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
import math

def usage():
print "Usage: ", sys.argv[0], "id frame_id radius [r, g, b]"
print("Usage: ", sys.argv[0], "id frame_id radius [r, g, b]")

class Drawer3DCircle:
RESOLUTION = 20
Expand Down
8 changes: 4 additions & 4 deletions jsk_pcl_ros/scripts/dump_depth_error.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,13 @@ def callback(msg):
for bin_index, msg_and_errs in bins.items():
if len(msg_and_errs) < 5:
continue
print "Bin: {0}m ~ {1}m".format(grid * bin_index, grid * (bin_index + 1))
print " Sample:", len(msg_and_errs)
print("Bin: {0}m ~ {1}m".format(grid * bin_index, grid * (bin_index + 1)))
print(" Sample:", len(msg_and_errs))
errs = [err for (msg, err) in msg_and_errs]
mean = np.mean(errs, axis=0)
stddev = np.std(errs, axis=0)
print " Mean:", mean
print " Stddev:", stddev
print(" Mean:", mean)
print(" Stddev:", stddev)
data.xs.append(msg.true_depth)
data.ys.append(msg.observed_depth)
pub.publish(data)
Expand Down
8 changes: 4 additions & 4 deletions jsk_pcl_ros/scripts/in_hand_recognition_manager.py
Original file line number Diff line number Diff line change
Expand Up @@ -55,8 +55,8 @@ def pose_diff_cb(pose_stamped):
try:
teacher_pose_stamped.header.stamp = rospy.Time(0)
teacher_pose_stamped_recog_frame = listener.transformPose(pose_stamped.header.frame_id, teacher_pose_stamped)
except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException, tf.Exception), e:
print "tf error: %s" % e
except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException, tf.Exception) as e:
print("tf error: %s" % e)
return
teacher_pose_mat = (get_mat_from_pose(teacher_pose_stamped_recog_frame.pose))
diff_pose_mat = (get_mat_from_pose(pose_stamped.pose))
Expand All @@ -70,8 +70,8 @@ def pose_diff_cb(pose_stamped):
try:
new_pose_stamped.header.stamp = rospy.Time(0)
new_pose_stamped_for_renew = listener.transformPose(teacher_pose_stamped.header.frame_id, new_pose_stamped)
except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException, tf.Exception), e:
print "tf error: %s" % e
except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException, tf.Exception) as e:
print("tf error: %s" % e)
return
pose_teacher_cb(new_pose_stamped_for_renew)
renew_flag = False
Expand Down
4 changes: 2 additions & 2 deletions jsk_pcl_ros/scripts/plot_depth_error.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,8 @@
plt.plot(X, line_y_ransac, "r--",
label="{0} x + {1}".format(model_ransac.estimator_.coef_[0][0],
model_ransac.estimator_.intercept_[0]))
print "{0} x + {1}".format(model_ransac.estimator_.coef_[0][0],
model_ransac.estimator_.intercept_[0])
print("{0} x + {1}".format(model_ransac.estimator_.coef_[0][0],
model_ransac.estimator_.intercept_[0]))
plt.grid()
plt.xlabel("Distance [m]")
plt.ylabel("Standard Deviation [m]")
Expand Down
2 changes: 1 addition & 1 deletion jsk_pcl_ros/scripts/plot_gaussian.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
import sys

if len(sys.argv) != 3:
print "plot_gaussian.py mean variance"
print("plot_gaussian.py mean variance")
sys.exit(1)
mean = float(sys.argv[1])
variance = float(sys.argv[2])
Expand Down
2 changes: 1 addition & 1 deletion jsk_pcl_ros/scripts/renew_tracking.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ def cloud_cb(cloud):
setCloud = rospy.ServiceProxy('particle_filter_tracker/renew_model', SetPointCloud2)
setCloud(cloud, track_target_name)
rospy.loginfo("Success renew_tracking service");
except rospy.ServiceException, e:
except rospy.ServiceException as e:
rospy.loginfo("Failed to call renew_tracking service")

if __name__ == "__main__":
Expand Down
4 changes: 2 additions & 2 deletions jsk_pcl_ros/scripts/tower_detect_viewer_server.py
Original file line number Diff line number Diff line change
Expand Up @@ -301,8 +301,8 @@ def clickCB(self, msg):
def imageCB(self, data):
try:
self.cv_image = self.bridge.imgmsg_to_cv(data, "bgr8")
except CvBridgeError, e:
print e
except CvBridgeError as e:
print(e)
def publishState(self):
self.state.publish()
def spin(self):
Expand Down
2 changes: 1 addition & 1 deletion jsk_perception/node_scripts/binpack_rect_array.py
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ def bin_pack(self, rects):
#blocks.sort(key=lambda x: x.rect.width*x.rect.height, reverse=True)
blocks.sort(reverse=True)
packer.fit(blocks)
print (packer.root.rect.width, packer.root.rect.height)
print((packer.root.rect.width, packer.root.rect.height))
return (packer.root.rect, blocks)
# for block in blocks:
# if block.fit_location:
Expand Down
10 changes: 5 additions & 5 deletions jsk_perception/node_scripts/matchtemplate.py
Original file line number Diff line number Diff line change
Expand Up @@ -149,8 +149,8 @@ def set_reference (self, rect):
cv_image = self.bridge.imgmsg_to_cv2(
self.reference_image_msg, "bgr8")
self.set_template('',ref_image=cv_image, ref_rect=rect)
except CvBridgeError, e:
print e
except CvBridgeError as e:
print(e)

#
# Callback Functions (lock require)
Expand All @@ -164,7 +164,7 @@ def set_reference_point_callback (self, msg): # PointStamped
pt[1]-self.default_template_size[1]/2,
self.default_template_size[0], self.default_template_size[1])
self.set_reference(rect)
print rect
print(rect)
search_rect = (pt[0]-self.default_search_size[0]/2,
pt[1]-self.default_search_size[1]/2,
self.default_search_size[0],self.default_search_size[1])
Expand Down Expand Up @@ -331,8 +331,8 @@ def ser_image_callback (self, msg):
:reference_size[1], :reference_size[0], :] = \
reference_image.copy()

except CvBridgeError, e:
print e
except CvBridgeError as e:
print(e)

self.lockobj.release()

Expand Down
2 changes: 1 addition & 1 deletion jsk_perception/node_scripts/random_forest_server.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ def initWithFileModel(cls, filename):
def classifyData(self, req):
ret = []
for data in req.data:
print data
print(data)
ret.append(" ".join([
str(predict_data)
for predict_data in self.clf.predict([data.point])]))
Expand Down
2 changes: 1 addition & 1 deletion jsk_perception/node_scripts/solidity_rag_merge.py
Original file line number Diff line number Diff line change
Expand Up @@ -129,7 +129,7 @@ def masked_slic(img, mask, n_segments, compactness):
n_labels = len(np.unique(labels))
try:
mask = ndi.binary_closing(mask, structure=np.ones((3, 3)), iterations=1)
except IndexError, e:
except IndexError as e:
rospy.logerr(e)
return
labels[mask == 0] = 0 # set bg_label
Expand Down
14 changes: 7 additions & 7 deletions jsk_perception/sample/random_forest_client_sample.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,17 +51,17 @@
answer = 0
req_point.point = target
req.data.append(req_point)
print OKGREEN,"Send Request ====================> Answer",ENDC
print OKGREEN," ",req_point.point," : ",str(answer),ENDC
print(OKGREEN,"Send Request ====================> Answer",ENDC)
print(OKGREEN," ",req_point.point," : ",str(answer),ENDC)
response = predict_data(req)
print WARNING,"Get the result : ",ENDC
print WARNING,response.classifications,ENDC
print(WARNING,"Get the result : ",ENDC)
print(WARNING,response.classifications,ENDC)
succeed = int(float(response.classifications[0])) == answer
if succeed:
print OKBLUE,"Succeed!!!",ENDC
print(OKBLUE,"Succeed!!!",ENDC)
else:
print FAIL,"FAIL...",FAIL
print "--- --- --- ---"
print(FAIL,"FAIL...",FAIL)
print("--- --- --- ---")

# Config for plotting
fig = plt.figure()
Expand Down
6 changes: 3 additions & 3 deletions jsk_perception/scripts/check_cascadeclassifier.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

def main():
if len(sys.argv) < 3:
print "Usage: check_cascadeclassifier.py cascade.xml [image_files ...]"
print("Usage: check_cascadeclassifier.py cascade.xml [image_files ...]")
sys.exit(1)
classifier_file = sys.argv[1]
files = sys.argv[2:]
Expand All @@ -20,9 +20,9 @@ def main():
cv2.rectangle(img,(x,y),(x+w,y+h),(0,0,255),2)
cv2.imshow('img', img)
cv2.waitKey(100)
except KeyboardInterrupt, e:
except KeyboardInterrupt as e:
raise e
except Exception, e:
except Exception as e:
pass

if __name__ == "__main__":
Expand Down
4 changes: 2 additions & 2 deletions jsk_perception/scripts/create_bof_dataset.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,8 @@ def cmd_extract_bof(data_path, output, data_size=1):
bof = BagOfFeatures()
try:
bof.fit(X)
except MemoryError, e:
print('data_size: {} ({} * {})'.format(n_data, data_size, n_data_all))
except MemoryError as e:
print(('data_size: {} ({} * {})'.format(n_data, data_size, n_data_all)))
print(e)
# save bof extractor
print('saving bof')
Expand Down
2 changes: 1 addition & 1 deletion jsk_perception/scripts/create_sift_dataset.py
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ def create_sift_dataset():
targets, pos_list, scale_list, ori_list, desc_list = [], [], [], [], []
for i, (filename, target) in enumerate(zip(bunch_files.filenames,
bunch_files.target)):
print('filename: {}, label: {}'.format(filename, target))
print(('filename: {}, label: {}'.format(filename, target)))
targets.append(target)
# extract feature
img = cv2.imread(filename, 0)
Expand Down
2 changes: 1 addition & 1 deletion jsk_perception/scripts/opencv_traindata_rejector.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ def main():
width = int(width)
height = int(height)
if os.path.exists(fname):
print "Opening " + fname
print("Opening " + fname)
img = cv2.imread(fname)
cv2.rectangle(img, (x, y),
(x + width, y + height),
Expand Down
6 changes: 3 additions & 3 deletions jsk_perception/scripts/sklearn_classifier_trainer.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,14 +41,14 @@ def main():
clf = LogisticRegression()
else:
raise ValueError('unsupported classifier')
print('fitting {0}'.format(args.classifier))
print(('fitting {0}'.format(args.classifier)))
clf.fit(X_train, y_train)
clf.target_names_ = target_names
with gzip.open(args.output, 'wb') as f:
pickle.dump(clf, f)
y_pred = clf.predict(X_test)
print('score of classifier: {}'.format(accuracy_score(y_test, y_pred)))
print(classification_report(y_test, y_pred, target_names=target_names))
print(('score of classifier: {}'.format(accuracy_score(y_test, y_pred))))
print((classification_report(y_test, y_pred, target_names=target_names)))


if __name__ == '__main__':
Expand Down
4 changes: 2 additions & 2 deletions jsk_perception/test/test_sparse_image.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,8 @@ def _publish(self):
try:
self.edgemsg.header.stamp = rospy.Time.now()
self.pub.publish(self.edgemsg)
except CvBridgeError, e:
print e
except CvBridgeError as e:
print(e)

def _check_img_msg_diff(self, msg1, msg2):
cnt = 0
Expand Down
Loading

0 comments on commit 313060f

Please sign in to comment.