Skip to content

Commit

Permalink
Added Timeout to calibrate_hand_finder (#230)
Browse files Browse the repository at this point in the history
* Added timeout to calibrate_hand_finder launch file. So that when using the close_everything icon it doesn't wait 120 seconds to find a hand.

* Update calibrate_hand_finder.py

* Updated year.

* Added timeout as default

* Switched to const.

* Fixed year in file.

* Fixed linter error.
  • Loading branch information
BenStarmerSmith authored Feb 22, 2023
1 parent 49b93a0 commit 1b61d62
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 10 deletions.
4 changes: 3 additions & 1 deletion sr_utilities/launch/calibrate_hand_finder.launch
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<!--
Copyright 2022 Shadow Robot Company Ltd.
Copyright 2022-2023 Shadow Robot Company Ltd.
This program is free software: you can redistribute it and/or modify it
under the terms of the GNU General Public License as published by the Free
Software Foundation version 2 of the License.
Expand All @@ -12,8 +12,10 @@
-->
<launch>
<arg name="node_shutdown" default="false" />
<arg name="node_timeout" default="120" />

<node name="calibrate_hand" pkg="sr_utilities" type="calibrate_hand_finder.py" output="screen">
<param name="node_shutdown" value="$(arg node_shutdown)" />
<param name="node_timeout" value="$(arg node_timeout)" />
</node>
</launch>
17 changes: 8 additions & 9 deletions sr_utilities/scripts/sr_utilities/calibrate_hand_finder.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/usr/bin/env python3

# Copyright 2014, 2020, 2022, 2023 Shadow Robot Company Ltd.
# Copyright 2014, 2020, 2022-2023 Shadow Robot Company Ltd.
#
# This program is free software: you can redistribute it and/or modify it
# under the terms of the GNU General Public License as published by the Free
Expand All @@ -23,15 +23,18 @@
from std_srvs.srv import Empty


CALIBRATE_TIMEOUT = 120.0


class CalibrateHand:
"""
This class resets all the motor boards of the Shadow Hand E present in the system.
On reset, the motor board firmware causes a jiggle and zeroes the tendon strain gauges.
Once the hands have been successfully reset, this class publishes True on the topic /calibrated
"""

def __init__(self):
rospy.wait_for_service("controller_manager/load_controller", timeout=120.0)
def __init__(self, timeout=CALIBRATE_TIMEOUT):
rospy.wait_for_service("controller_manager/load_controller", timeout=timeout)
self.pub_calibrated = rospy.Publisher('calibrated', Bool, queue_size=1, latch=True)

@staticmethod
Expand Down Expand Up @@ -94,16 +97,12 @@ def main():
rospy.init_node('calibration', anonymous=True)
# By default should be enabled, except when shutting system down
ros_node_shutdown = rospy.get_param("~node_shutdown", False)

calibrate_class = CalibrateHand()

ros_node_timeout = rospy.get_param("~node_timeout", CALIBRATE_TIMEOUT)
calibrate_class = CalibrateHand(ros_node_timeout)
services = calibrate_class.generate_reset_services_list()

calibrate_class.pub_calibrated.publish(False)

if not calibrate_class.calibrate(services):
sys.exit(3)

calibrate_class.pub_calibrated.publish(True)

print("Hand calibration complete")
Expand Down

0 comments on commit 1b61d62

Please sign in to comment.