def test_frame_parsing(self):
        frame = Frame.parse_string("""
			<frame id="7" name="paola" source="me">
				<word name="wow" />
				<byte name="incredible" />
				<word name="hihi" />
			</frame>
		""",
                                   context=Context(devices=self.device_list))

        # Parse properties
        self.assertEqual(frame.source, "me")
        self.assertEqual(frame.dest, "mlk")  # broadcast by default

        self.assertEqual(frame.name, "paola")
        self.assertEqual(frame.id, 7)
        self.assertEqual(len(frame.params), 3)

        # Parse childrens
        self.assertEqual(frame.params[0].name, "wow")
        self.assertEqual(frame.params[0].byte_start, 1)

        self.assertEqual(frame.params[1].name, "incredible")
        self.assertEqual(frame.params[1].byte_start, 3)

        self.assertEqual(frame.params[2].name, "hihi")
        self.assertEqual(frame.params[2].byte_start, 4)
    def __init__(self):
        self.nodes = NodeStatusHandler()
        self.start_signal_pub = rospy.Publisher(Topics.START_SIGNAL_TOPIC,
                                                StartRobot,
                                                queue_size=10)
        self.spin_callbacks = []
        self.can_subscribers = []

        # Parse devices
        self.devices: DeviceList = DeviceList.parse_file(
            "can/devices.xml", package="interface_description")

        # Then frames
        self.frames: Dict[str, Frame] = FrameList.parse_file(
            "can/frames.xml",
            package="interface_description",
            context=Context(devices=self.devices))

        # Create can bus with given interface
        self.bus = can.interface.Bus(
            rospy.get_param("/interface/can_interface/device",
                            default="vcan0"))
        self.can_input_thread = threading.Thread(
            name="can_input", target=self.wait_for_can_message)

        # Start thread
        self.can_input_thread.start()

        # Wait for controller and scheduler
        self.nodes.require("controller", "ai")
        self.nodes.require("scheduler", "ai")
        self.nodes.set_wait_callback(self.nodes_ready)
        self.nodes.wait_for_nodes(6)
    def __init__(self):
        super().__init__()
        self.set_node_status("serial_interface", "interface", NodeStatus.INIT)

        # Parse devices
        self.devices: DeviceList = DeviceList.parse_file(
            "can/devices.xml", package="interface_description")

        # Then frames
        self.frames: Dict[str, Frame] = FrameList.parse_file(
            "can/frames.xml",
            package="interface_description",
            context=Context(devices=self.devices))

        # Create serial bus bus with given interface
        self.serials = [
            SerialBus("/dev/ttyUSB0", self),
            SerialBus("/dev/ttyUSB1", self)
        ]

        self.subscriber: Subscriber = Subscriber("/can_interface/out", CanData,
                                                 self.on_ros_message)
        self.publisher: Publisher = Publisher("/can_interface/in",
                                              CanData,
                                              queue_size=10)

        # Declare can_interface ready
        self.set_node_status("serial_interface", "interface", NodeStatus.READY)
Esempio n. 4
0
	def __init__(self):
		super().__init__()
		self.set_node_status("can_interface", "interface", NodeStatus.INIT)

		# Parse devices
		self.devices: DeviceList = DeviceList.parse_file(
			"can/devices.xml",
			package="interface_description"
		)

		# Then frames
		self.frames: Dict[str, Frame] = FrameList.parse_file(
			"can/frames.xml",
			package="interface_description",
			context=Context(devices=self.devices)
		)

		# Create can bus with given interface
		self.bus = can.interface.Bus(rospy.get_param("/interface/can_interface/device", default="can0"))
		self.can_input_thread = threading.Thread(name="can_input", target=self.wait_for_can_message)

		# TODO /can_interface/out as a service
		self.subscriber: Subscriber = Subscriber("/can_interface/out", CanData, self.on_ros_message)
		self.publisher: Publisher = Publisher("/can_interface/in", CanData, queue_size=100)

		# Start thread
		self.can_input_thread.start()

		# Declare can_interface ready
		self.set_node_status("can_interface", "interface", NodeStatus.READY)
Esempio n. 5
0
	def test_context_passing(self):
		global SomeClass
		global YetAnotherClass

		YetAnotherClass = Parsable(name="array_attr")(YetAnotherClass)
		SomeClass = Parsable(name="o", children = [ BindList(type=YetAnotherClass, to="array_attr") ])(SomeClass)

		parsed = SomeClass.parse_string("<o><array_attr /></o>", context=Context(name="hello"))

		self.assertEqual(parsed.str_attr, "hello", "original context is passed")
		self.assertEqual(len(parsed.array_attr), 1)
		self.assertEqual(parsed.array_attr[0].wow, 76, "context is passed with additional args")
    def __parsed__(self, context: Context):
        super().__parsed__(context)

        for i in range(len(self.children)):
            child = self.children[i]

            # Non native action children
            if type(child) == Action and not child.native:
                # Recover list format
                child.arguments = child.arguments.to_list()

                # Create adequate context
                child_context = Context(**context.params)
                child_context.parent = child

                # Parse children with context
                self.children[i] = ActionGroup.parse_file(
                    context.get("folder") + child.name + ".xml",
                    context=child_context)

            # Set children parent
            self.children[i].parent = self
    def test_frame_list_parsing(self):
        frame_list = FrameList.parse_string(
            """
			<frames>
				<frame name="go_girl" id="5" />
				<frame name="go_girl_lol" id="1" />
			</frames>
		""",
            context=Context(devices=self.device_list))

        self.assertIn(5, frame_list.by_id)
        self.assertIn(1, frame_list.by_id)

        self.assertIn("go_girl", frame_list.by_name)
        self.assertIn("go_girl_lol", frame_list.by_name)

        self.assertEqual(frame_list.by_id[5], frame_list.by_name["go_girl"])
        self.assertEqual(frame_list.by_id[1],
                         frame_list.by_name["go_girl_lol"])
Esempio n. 8
0
    def __parsed__(self, context: Context):
        devices = context.get("devices")

        self.source = self.source if self.source is not None else devices.broadcast.name
        self.dest = self.dest if self.dest is not None else devices.broadcast.name

        # Check that devices exists
        if self.source not in devices.by_name:
            raise ParsingException("{} is not a valid device".format(
                self.source))

        elif self.dest not in devices.by_name:
            raise ParsingException("{} is not a valid device".format(
                self.dest))

        # Compute params byte_start property
        current_offset: int = 1
        for param in self.params:
            param.byte_start = current_offset
            current_offset += param.size
	def __init__(self, dev="vcan0", callback=None):
		self.callback = callback

		# Parse devices
		self.devices: DeviceList = DeviceList.parse_file(
			"can/devices.xml",
			package="interface_description"
		)

		# Then frames
		self.frames: Dict[str, Frame] = FrameList.parse_file(
			"can/frames.xml",
			package="interface_description",
			context=Context(devices=self.devices)
		)

		# Create can bus with given interface
		self.bus = can.interface.Bus(dev)
		self.can_input_thread = threading.Thread(name="can_input", target=self.wait_for_can_message)

		# Start thread
		self.can_input_thread.start()
    def __parsed__(self, context: Context):
        self.oui = True

        if "bob" in context.params:
            self.wow = context.get("bob")
 def __before_children__(self, context: Context):
     context.set("bob", 76)
 def __parsed__(self, context: Context):
     if "name" in context.params:
         self.str_attr = context.get("name")