Skip to content
Snippets Groups Projects
Commit e8cb206a authored by Simon Wittl's avatar Simon Wittl
Browse files

thd mock up

parent b390ee00
No related branches found
No related tags found
No related merge requests found
import artistlib.hardware
from ..base_hardware_service import BaseHardwareInterfaceService, AquireProjection, ReachabilityCheck
from rq_controller.common import PyProjection
import ros2_numpy
import numpy as np
from pathlib import Path
from sensor_msgs.msg import Image
import rclpy
class ThdRoboCTHardwareInterface(BaseHardwareInterfaceService):
def __init__(self, node_name: str = 'rq_hardware_interface_service'):
super().__init__(node_name)
def aquire_projection_callback(self,
request: AquireProjection.Request,
response: AquireProjection.Response):
pass
def check_reachability_callback(self,
request: ReachabilityCheck.Request,
response: ReachabilityCheck.Response):
pass
def main(args=None):
rclpy.init(args=args)
minimal_service = ThdRoboCTHardwareInterface()
rclpy.spin(minimal_service)
rclpy.shutdown()
if __name__ == '__main__':
main()
......@@ -21,6 +21,7 @@ setup(
entry_points={
'console_scripts': [
'service_artist = rq_hardware.artist.artist_harware_service:main',
'service_thd_roboct = rq_hardware.thd_roboct.thd_roboct_service:main',
'client = rq_hardware.hardware_client:main'
],
},
......
{
"focal_spot_position_mm": [
0.0,
100.0,
-1.2246063538223773e-13,
-1000.0,
0.0
],
"focal_spot_orientation_matrix": [
......@@ -22,20 +22,20 @@
]
],
"detector_center_position_mm": [
0.0,
-100.0,
1.2246063538223773e-13,
1000.0,
0.0
],
"detector_center_orientation_matrix": [
[
1.0,
0.0,
0.0
-1.0,
-2.7191723402317286e-32,
1.2246063538223773e-16
],
[
0.0,
2.220446049250313e-16,
-1.0
1.2246063538223773e-16,
-2.220446049250313e-16,
1.0
],
[
0.0,
......@@ -44,10 +44,10 @@
]
],
"detector_center_orientation_quat": [
4.329637285359677e-17,
0.7071067811865475,
0.0,
0.0,
0.7071067811865477
0.7071067811865477,
4.3296372853596783e-17
],
"detector_count_px": [
1000,
......
No preview for this file type
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment