def test_posctl(self):
        # FIXME: this must go ASAP when arming is implemented
        manIn = ManualInput()
        manIn.arm()
        manIn.offboard_posctl()

        self.assertTrue(self.arm(), "Could not arm")
        self.rateSec.sleep()
        self.rateSec.sleep()
        self.assertTrue(self.controlMode.flag_armed, "flag_armed is not set after 2 seconds")

        # prepare flight path
        positions = (
            (0,0,0),
            (2,2,2),
            (2,-2,2),
            (-2,-2,2),
            (2,2,2))

        for i in range(0, len(positions)):
            self.reach_position(positions[i][0], positions[i][1], positions[i][2], 120)
        
        # does it hold the position for Y seconds?
        positionHeld = True
        count = 0
        timeout = 50
        while(count < timeout):
            if(not self.is_at_position(2, 2, 2, 0.5)):
                positionHeld = False
                break
            count = count + 1
            self.rate.sleep()

        self.assertTrue(count == timeout, "position could not be held")
    def test_posctl(self):
        # FIXME: this must go ASAP when arming is implemented
        manIn = ManualInput()
        manIn.arm()
        manIn.offboard_posctl()

        self.assertTrue(self.arm(), "Could not arm")
        self.rateSec.sleep()
        self.rateSec.sleep()
        self.assertTrue(self.controlMode.flag_armed,
                        "flag_armed is not set after 2 seconds")

        # prepare flight path
        positions = ((0, 0, 0), (2, 2, 2), (2, -2, 2), (-2, -2, 2), (2, 2, 2))

        for i in range(0, len(positions)):
            self.reach_position(positions[i][0], positions[i][1],
                                positions[i][2], 120)

        # does it hold the position for Y seconds?
        positionHeld = True
        count = 0
        timeout = 50
        while (count < timeout):
            if (not self.is_at_position(2, 2, 2, 0.5)):
                positionHeld = False
                break
            count = count + 1
            self.rate.sleep()

        self.assertTrue(count == timeout, "position could not be held")