Skip to content

Commit 75ec783

Browse files
committed
Fix up argparse help output.
Signed-off-by: Chris Lalancette <[email protected]>
1 parent 4bd4e8a commit 75ec783

File tree

2 files changed

+6
-6
lines changed

2 files changed

+6
-6
lines changed

image_tools_py/cam2image_py.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -73,18 +73,18 @@ def main(args=None):
7373
'-b', '--burger', dest='burger_mode', action='store_true', default=False,
7474
help='Produce images of burgers rather than connecting to a camera')
7575
parser.add_argument(
76-
'-d', '--depth', dest='depth', action='store', default=qos_profile_system_default.depth, type=int,
76+
'-d', '--depth', dest='depth', action='store', default=int(qos_profile_system_default.depth), type=int,
7777
help='Queue depth')
7878
parser.add_argument(
7979
'-f', '--frequency', dest='frequency', action='store', default=30, type=int,
8080
help='Publish frequency in Hz')
8181
parser.add_argument(
82-
'-k', '--keep', dest='history_policy', action='store', default=qos_profile_system_default.history,
82+
'-k', '--keep', dest='history_policy', action='store', default=int(qos_profile_system_default.history),
8383
type=int, choices=[0, 1],
8484
help='History QoS setting, 0 - keep last sample, 1 - keep all the samples')
8585
parser.add_argument(
8686
'-r', '--reliability', dest='reliability_policy', action='store',
87-
default=qos_profile_system_default.reliability, type=int, choices=[0, 1],
87+
default=int(qos_profile_system_default.reliability), type=int, choices=[0, 1],
8888
help='Reliability QoS setting, 0 - best effort, 1 - reliable')
8989
parser.add_argument(
9090
'-s', '--show', dest='show_camera', action='store', default=0, type=int, choices=[0, 1],

image_tools_py/showimage_py.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -48,15 +48,15 @@ def main(args=None):
4848
# Parse the command-line options.
4949
parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
5050
parser.add_argument(
51-
'-d', '--depth', dest='depth', action='store', default=qos_profile_system_default.depth, type=int,
51+
'-d', '--depth', dest='depth', action='store', default=int(qos_profile_system_default.depth), type=int,
5252
help='Queue depth')
5353
parser.add_argument(
54-
'-k', '--keep', dest='history_policy', action='store', default=qos_profile_system_default.history,
54+
'-k', '--keep', dest='history_policy', action='store', default=int(qos_profile_system_default.history),
5555
type=int, choices=[0, 1],
5656
help='History QoS setting, 0 - keep last sample, 1 - keep all the samples')
5757
parser.add_argument(
5858
'-r', '--reliability', dest='reliability_policy', action='store',
59-
default=qos_profile_system_default.reliability, type=int, choices=[0, 1],
59+
default=int(qos_profile_system_default.reliability), type=int, choices=[0, 1],
6060
help='Reliability QoS setting, 0 - best effort, 1 - reliable')
6161
parser.add_argument(
6262
'-s', '--show', dest='show_camera', action='store', default=1, type=int, choices=[0, 1],

0 commit comments

Comments
 (0)