diff --git a/src/axidraw_controller/CMakeLists.txt b/src/axidraw_controller/CMakeLists.txt index 5f58168..bc9b649 100644 --- a/src/axidraw_controller/CMakeLists.txt +++ b/src/axidraw_controller/CMakeLists.txt @@ -29,6 +29,11 @@ ament_target_dependencies(axidraw_controller "robot_interfaces" ) + +install(TARGETS + axidraw_controller + DESTINATION lib/${PROJECT_NAME}) + install(PROGRAMS src/py/axidraw_serial.py DESTINATION lib/${PROJECT_NAME} diff --git a/src/axidraw_controller/src/py/axidraw_serial.py b/src/axidraw_controller/src/py/axidraw_serial.py index e2a81f3..4712aa7 100644 --- a/src/axidraw_controller/src/py/axidraw_serial.py +++ b/src/axidraw_controller/src/py/axidraw_serial.py @@ -8,6 +8,7 @@ from std_msgs.msg import Empty import rclpy from rclpy.node import Node +from rclpy.qos import QoSProfile #TODO delete this @@ -54,10 +55,10 @@ class AxidrawSerial(Node): while not self.init_serial(port): self.get_logger().error("Failed to connect to axidraw on port:{}".format(port)) - self.move_sub = self.create_subscription(Point, 'axidraw_move', move_callback) - self.penup_sub = self.create_subscription(Empty, 'axidraw_penup', penup_callback) - self.pendown_sub = self.create_subscription(Empty, 'axidraw_pendown', pendown_callback) - self.path_sub = self.create_subscription(Points, 'axidraw_path', stroke_callback) + self.move_sub = self.create_subscription(Point, 'axidraw_move', self.move_callback, qos_profile=QoSProfile(depth=1)) + self.penup_sub = self.create_subscription(Empty, 'axidraw_penup', self.penup_callback, qos_profile=QoSProfile(depth=1)) + self.pendown_sub = self.create_subscription(Empty, 'axidraw_pendown', self.pendown_callback, qos_profile=QoSProfile(depth=1)) + self.path_sub = self.create_subscription(Points, 'axidraw_path', self.stroke_callback, qos_profile=QoSProfile(depth=1)) def get_status(self, request, response): response.status = status.get(request.resource, "Resource '{}' not found.".format(request.resource)) @@ -93,7 +94,7 @@ class AxidrawSerial(Node): self.ad.pendown() self.set_ready() - def path_callback(self, msg): + def stroke_callback(self, msg): self.set_busy() self.get_logger().info("Received path: {}".format(msg))