添加相机数据采集服务客户端
This commit is contained in:
@@ -43,6 +43,9 @@ setup(
|
||||
'get_camera_pose_node = vision_detect.get_camera_pose:main',
|
||||
|
||||
'detect_node = vision_detect.detect_node:main',
|
||||
|
||||
'collect_data_node = vision_detect.collect_data_node:main',
|
||||
'collect_data_client = vision_detect.collect_data_client:main',
|
||||
],
|
||||
},
|
||||
)
|
||||
|
||||
44
vision_detect/vision_detect/collect_data_client.py
Normal file
44
vision_detect/vision_detect/collect_data_client.py
Normal file
@@ -0,0 +1,44 @@
|
||||
import rclpy
|
||||
from rclpy.node import Node
|
||||
from rclpy.parameter import Parameter
|
||||
|
||||
from std_srvs.srv import SetBool
|
||||
|
||||
|
||||
def result_callback(result):
|
||||
pass
|
||||
|
||||
|
||||
def main(args=None):
|
||||
def timer_callback():
|
||||
start_sign = node.get_parameter("collect_sign").value
|
||||
end_sign = node.get_parameter("end_sign").value
|
||||
|
||||
if start_sign:
|
||||
request = SetBool.Request()
|
||||
request.data = True
|
||||
client.call_async(request).add_done_callback(result_callback)
|
||||
node.set_parameters([Parameter('collect_sign', Parameter.Type.BOOL, False)])
|
||||
|
||||
|
||||
if end_sign:
|
||||
request = SetBool.Request()
|
||||
request.data = False
|
||||
client.call_async(request).add_done_callback(result_callback)
|
||||
node.set_parameters([Parameter('end_sign', Parameter.Type.BOOL, False)])
|
||||
|
||||
|
||||
rclpy.init(args=args)
|
||||
node = Node("collect_data_client")
|
||||
client = node.create_client(SetBool, "/collect_data")
|
||||
while not client.wait_for_service(timeout_sec=1.0):
|
||||
node.get_logger().info('Service not available, waiting again...')
|
||||
node.declare_parameter("collect_sign", False)
|
||||
node.declare_parameter("end_sign", False)
|
||||
node.create_timer(0.5, timer_callback)
|
||||
try:
|
||||
rclpy.spin(node)
|
||||
except KeyboardInterrupt:
|
||||
pass
|
||||
finally:
|
||||
node.destroy_node()
|
||||
@@ -2,7 +2,6 @@ import os
|
||||
import json
|
||||
|
||||
import cv2
|
||||
import numpy as np
|
||||
|
||||
import rclpy
|
||||
from rclpy.node import Node
|
||||
|
||||
Reference in New Issue
Block a user