From 43796926fa12f33968c8448f12a0b23a5f188483 Mon Sep 17 00:00:00 2001
From: swittl <simon.wittl@th-deg.de>
Date: Thu, 11 Jul 2024 09:45:30 +0200
Subject: [PATCH] added proj example

---
 .gitignore                                   |  3 +-
 examples/01_try_mesh.py                      |  2 +-
 examples/02_try_recahbility_map.py           |  5 +--
 examples/04_aquire_projection.py             | 33 ++++++++++++++++++++
 rq_hardware/base_hardware_service.py         |  4 +--
 rq_hardware/hardware_client.py               |  2 +-
 rq_hardware/thd_roboct/thd_roboct_service.py |  5 +--
 7 files changed, 45 insertions(+), 9 deletions(-)
 create mode 100644 examples/04_aquire_projection.py

diff --git a/.gitignore b/.gitignore
index f391642..ea231de 100644
--- a/.gitignore
+++ b/.gitignore
@@ -1 +1,2 @@
-/.vscode/
\ No newline at end of file
+/.vscode/
+/temp/
\ No newline at end of file
diff --git a/examples/01_try_mesh.py b/examples/01_try_mesh.py
index 700b048..94f90d1 100644
--- a/examples/01_try_mesh.py
+++ b/examples/01_try_mesh.py
@@ -10,7 +10,7 @@ from rq_hardware.artist.artist_hardware_service import ArtistHardwareInterface
 
 class MeshPublisher(Node):
     def __init__(self):
-        super().__init__('mesh_publisher')
+        super().__init__('mesh_publisher', namespace='rq')
         self.publisher = self.create_publisher(Mesh, 'rq_artist_collision_mesh_mm', 10)
 
     def publish_mesh(self, msg):
diff --git a/examples/02_try_recahbility_map.py b/examples/02_try_recahbility_map.py
index 187d61e..eaab998 100644
--- a/examples/02_try_recahbility_map.py
+++ b/examples/02_try_recahbility_map.py
@@ -12,7 +12,7 @@ from rq_hardware.hardware_client import HardwareClient
 
 rclpy.init()
 
-client = HardwareClient(namespace="rq")
+client = HardwareClient()
 roi = PyRegionOfIntrest.dummy()
 roi.dimensions_mm = roi.dimensions_mm * 100.
 roi.resolution_mm = roi.resolution_mm * 10.
@@ -26,4 +26,5 @@ volume = client.reachability_map_response_2_py(future.result())
 
 print(volume.shape)
 
-print(volume.array.sum())
\ No newline at end of file
+print(volume.array.sum())
+
diff --git a/examples/04_aquire_projection.py b/examples/04_aquire_projection.py
new file mode 100644
index 0000000..3f287b6
--- /dev/null
+++ b/examples/04_aquire_projection.py
@@ -0,0 +1,33 @@
+
+import rclpy
+import numpy as np
+
+from rq_controller.common import PyProjection
+from rq_hardware.hardware_client import HardwareClient
+
+import matplotlib.pyplot as plt
+
+rclpy.init()
+
+hardware_client = HardwareClient()
+
+proj = PyProjection.dummy()
+proj.focal_spot_mm = np.array([0., 0., 1000.])
+proj.detector_postion_mm = np.array([0., 0., -1000.])
+proj.detector_orientation_quad = np.array([0., 0., 0., 1.])
+
+
+proj.voltage_kv = 100.
+proj.current_ua = 40.
+
+
+future = hardware_client.aquire_projection(proj)
+
+rclpy.spin_until_future_complete(hardware_client, future)
+
+proj_response = hardware_client.projection_response_2_py(future.result())
+
+plt.imshow(proj_response.image)
+plt.show()
+
+
diff --git a/rq_hardware/base_hardware_service.py b/rq_hardware/base_hardware_service.py
index e968462..4c12e08 100644
--- a/rq_hardware/base_hardware_service.py
+++ b/rq_hardware/base_hardware_service.py
@@ -12,10 +12,10 @@ class BaseHardwareInterfaceService(Node):
     interface_type: str = 'Base'
     last_projection: PyProjection = None
     measurement_name: str = 'projection'
-    projection_tempfolder: Path = Path(r'C:\ros\ros\humble_embedded\rq_workflow\src\rq_hardware\temp')
+    projection_tempfolder: Path = Path(r'C:\dev\rq_workflow\src\rq_hardware\temp')
     
     def __init__(self, node_name: str = 'rq_base_hardware_interface_service'):
-        super().__init__(node_name)
+        super().__init__(node_name, namespace="rq")
         self.aquire_projection_srv = self.create_service(AquireProjection, 'aquire_projection', self.aquire_projection_callback)
         self.reachability_srv = self.create_service(ReachabilityCheck, 'check_reachability', self.check_reachability_callback)
         self.reachability_map_srv = self.create_service(ReachabilityMapCheck, 'check_reachability_map', self.check_reachability_map_callback)
diff --git a/rq_hardware/hardware_client.py b/rq_hardware/hardware_client.py
index e16e8b6..aafadba 100644
--- a/rq_hardware/hardware_client.py
+++ b/rq_hardware/hardware_client.py
@@ -13,7 +13,7 @@ import numpy as np
 class HardwareClient(Node):
 
     def __init__(self, **kwargs):
-        super().__init__('rq_hardware_client', **kwargs)
+        super().__init__('rq_hardware_client', namespace="rq", **kwargs)
         self.cli_projection = self.create_client(AquireProjection, 'aquire_projection')
         while not self.cli_projection.wait_for_service(timeout_sec=1.0):
             self.get_logger().info('projection service not available, waiting again...')
diff --git a/rq_hardware/thd_roboct/thd_roboct_service.py b/rq_hardware/thd_roboct/thd_roboct_service.py
index 94e20b7..da6c06d 100644
--- a/rq_hardware/thd_roboct/thd_roboct_service.py
+++ b/rq_hardware/thd_roboct/thd_roboct_service.py
@@ -33,7 +33,8 @@ try:
     from trajectory_toolbox.util.util_poses import Frame, ScanPoseList, ScanPoseTuple  # type: ignore
 
 except ModuleNotFoundError:
-    raise ModuleNotFoundError("Packages are spedific for the RoboCT of the Deggendorf Institute of Technology. Please Contact: simon.wittl@th-deg.de")
+    raise ModuleNotFoundError("Packages are spedific for the RoboCT of the Deggendorf Institute of Technology. \n" + 
+                              "Please Contact: simon.wittl@th-deg.de")
 
 
 class TurntablePlannerParameter:
@@ -44,7 +45,7 @@ class TurntablePlannerParameter:
 class ThdRoboCTHardwareInterface(BaseHardwareInterfaceService):
     interface_type: str = 'THD'
 
-    def __init__(self, node_name: str = 'rq_hardware_interface_service'):
+    def __init__(self, node_name: str = 'rq_thd_hardware_interface_service'):
 
         super().__init__(node_name)
 
-- 
GitLab