|
9 | 9 | from handeye_tf_service.srv import HandeyeTF
|
10 | 10 | from ament_index_python.resources import get_resource
|
11 | 11 |
|
| 12 | +from rcl_interfaces.msg import Parameter, ParameterType, ParameterValue |
| 13 | +from rcl_interfaces.srv import SetParameters |
| 14 | + |
12 | 15 | # Rqt widgets
|
13 | 16 | from rqt_gui_py.plugin import Plugin
|
14 | 17 | from python_qt_binding import QtCore
|
@@ -71,6 +74,11 @@ def __init__(self, context):
|
71 | 74 | self.widget.setObjectName(self.PLUGIN_TITLE)
|
72 | 75 | self.widget.setWindowTitle(self.PLUGIN_TITLE)
|
73 | 76 |
|
| 77 | + # parameter |
| 78 | + self.cli_param = self.node.create_client(SetParameters, '/grasp_modbus_server/set_parameters') |
| 79 | + while not self.cli_param.wait_for_service(timeout_sec=1.0): |
| 80 | + self.node.get_logger().info('service not available, waiting again...') |
| 81 | + |
74 | 82 | # Data
|
75 | 83 | self.Tsamples = []
|
76 | 84 |
|
@@ -313,6 +321,18 @@ def calibration(self):
|
313 | 321 | self.textedit.append("Failed to solve the hand-eye calibration.")
|
314 | 322 |
|
315 | 323 | def execution(self):
|
| 324 | + # Set calibration state to success |
| 325 | + req = SetParameters.Request() |
| 326 | + |
| 327 | + param = Parameter() |
| 328 | + param.name = "calibration_state" |
| 329 | + param.value.type = ParameterType.PARAMETER_INTEGER |
| 330 | + param.value.integer_value = 4 |
| 331 | + req.parameters.append(param) |
| 332 | + |
| 333 | + future = self.cli_param.call_async(req) |
| 334 | + rclpy.spin_until_future_complete(self.node, future) |
| 335 | + |
316 | 336 | # >>> Publish the camera-robot transform
|
317 | 337 | self.textedit.append('Publishing the camera TF ...')
|
318 | 338 | file_input = '/tmp/' + 'camera-robot.json'
|
|
0 commit comments