def GetInfoHandler(_):
     rosmsg = canros.srv.GetNodeInfoResponse()
     rosmsg.node_info = canros.copy_uavcan_ros(rosmsg.node_info,
                                               uavcan_node.node_info,
                                               request=False)
     setattr(rosmsg.node_info.status, canros.uavcan_id_field_name,
             uavcan_node.node_id)
     return rosmsg
 def handler(event):
     ros_req = canros.copy_uavcan_ros(self.Request_Type(),
                                      event.request,
                                      request=True)
     setattr(ros_req, canros.uavcan_id_field_name,
             event.transfer.source_node_id)
     try:
         ros_resp = self.ROS_ServiceProxy(ros_req)
     except rospy.ServiceException:
         return
     return canros.copy_ros_uavcan(self.UAVCAN_Type.Response(),
                                   ros_resp,
                                   request=False)
        def handler(event):
            uavcan_req = canros.copy_ros_uavcan(self.UAVCAN_Type.Request(),
                                                event,
                                                request=True)

            q = Queue(maxsize=1)

            def callback(event):
                q.put(event.response if event else None)

            uavcan_id = getattr(event, canros.uavcan_id_field_name)
            if uavcan_id == 0:
                return
            uavcan_node.request(
                uavcan_req, uavcan_id, callback,
                timeout=1)  # Default UAVCAN service timeout is 1 second

            uavcan_resp = q.get()
            if uavcan_resp is None:
                return
            return canros.copy_uavcan_ros(self.Response_Type(),
                                          uavcan_resp,
                                          request=False)
 def handler(event):
     ros_msg = canros.copy_uavcan_ros(self.Type(), event.message)
     if self.HasIdFeild:
         setattr(ros_msg, canros.uavcan_id_field_name,
                 event.transfer.source_node_id)
     self.ROS_Publisher.publish(ros_msg)