Skip to content
This repository was archived by the owner on Apr 8, 2024. It is now read-only.

Commit 22ea4ff

Browse files
committed
Add calibration_state parameter client
1 parent 7d311f1 commit 22ea4ff

File tree

1 file changed

+20
-0
lines changed

1 file changed

+20
-0
lines changed

grasp_utils/handeye_dashboard/src/handeye_dashboard/handeye_calibration.py

Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,9 @@
99
from handeye_tf_service.srv import HandeyeTF
1010
from ament_index_python.resources import get_resource
1111

12+
from rcl_interfaces.msg import Parameter, ParameterType, ParameterValue
13+
from rcl_interfaces.srv import SetParameters
14+
1215
# Rqt widgets
1316
from rqt_gui_py.plugin import Plugin
1417
from python_qt_binding import QtCore
@@ -71,6 +74,11 @@ def __init__(self, context):
7174
self.widget.setObjectName(self.PLUGIN_TITLE)
7275
self.widget.setWindowTitle(self.PLUGIN_TITLE)
7376

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+
7482
# Data
7583
self.Tsamples = []
7684

@@ -313,6 +321,18 @@ def calibration(self):
313321
self.textedit.append("Failed to solve the hand-eye calibration.")
314322

315323
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+
316336
# >>> Publish the camera-robot transform
317337
self.textedit.append('Publishing the camera TF ...')
318338
file_input = '/tmp/' + 'camera-robot.json'

0 commit comments

Comments
 (0)