diff --git a/.github/workflows/lint.yml b/.github/workflows/lint.yml index fe607d4..4fc7fc3 100644 --- a/.github/workflows/lint.yml +++ b/.github/workflows/lint.yml @@ -18,6 +18,9 @@ jobs: - name: Set up Python environment uses: actions/setup-python@v1 with: - python-version: "3.7" + python-version: "3.8" - name: flake8 Lint uses: py-actions/flake8@v1 + with: + ignore: "E203,E402,E501,F401,F841" + exclude: "logs/*,data/*,furuta_gym/logging/protobuf/*" diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 8c7fcf2..04036ec 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -55,7 +55,7 @@ repos: "--extend-ignore", "E203,E402,E501,F401,F841", "--exclude", - "logs/*,data/*", + "logs/*,data/*,furuta_gym/logging/protobuf/*", ] # yaml formatting @@ -64,7 +64,6 @@ repos: hooks: - id: prettier types: [yaml] - # # jupyter notebook cell output clearing # - repo: https://github.com/kynan/nbstripout # rev: 0.5.0 @@ -84,4 +83,4 @@ repos: # [ # "--extend-ignore=E203,E402,E501,F401,F841", # "--exclude=logs/*,data/*", -# ] \ No newline at end of file +# ] diff --git a/furuta_gym/robot.py b/furuta_gym/robot.py new file mode 100644 index 0000000..5be9848 --- /dev/null +++ b/furuta_gym/robot.py @@ -0,0 +1,34 @@ +import struct + +import matplotlib.pyplot as plt +import numpy as np +import serial +import simple_pid + + +class Robot: + def __init__(self, device="dev/ttyACM0", baudrate=921600): + self.ser = serial.Serial(device, baudrate) + + def step(self, motor_command: float): + """motor command is a float between -1 and 1.""" + direction = motor_command < 0 + # convert motor command to 16 bit unsigned int + int_motor_command = int(np.abs(motor_command) * (2**16 - 1)) + tx = b"\x10\x02" # start sequence + tx += b"\x01" # command type = STEP = 0x01 + tx += struct.pack("]" + "Text(0.5, 1.0, 'Motor Angles')" ] }, - "execution_count": 57, + "execution_count": 2, "metadata": {}, "output_type": "execute_result" }, { "data": { - "image/png": "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", + "image/png": "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", "text/plain": [ "
" ] @@ -57,7 +55,17 @@ }, { "data": { - "image/png": "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", + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", "text/plain": [ "
" ] @@ -69,41 +77,63 @@ "source": [ "angle_thresh = 0.5 # rad\n", "\n", - "ser = serial.Serial('/dev/ttyACM0', 57600)\n", - "Kp = 1.5\n", - "Ki = 5.0\n", + "robot = Robot(\"/dev/ttyACM1\")\n", + "Kp = 3.5\n", + "Ki = 20.0\n", "Kd = 0.1\n", "\n", - "PID = simple_pid.PID(Kp, Ki, Kd, setpoint=0)\n", + "pendulum_PID = simple_pid.PID(Kp, Ki, Kd, setpoint=0, sample_time=0.0004) # 2.5 khz\n", + "motor_pid = simple_pid.PID(0.2, 0.001, 0.000, setpoint=0, sample_time=None)\n", "actions = []\n", "motor_angles = []\n", "pendulum_angles = []\n", "\n", + "robot.reset_encoders()\n", "print(\"go\")\n", "\n", - "motor_angle, pendulum_angle = step(ser, 0)\n", + "input()\n", + "\n", + "motor_angle, pendulum_angle = robot.step(0)\n", "\n", + "nb_loops = 0\n", + "start = time.time()\n", + "\n", + "last_act = 0\n", "while True:\n", - " act = PID(np.sin(pendulum_angle))\n", - " act = -int(np.clip(act, -1, 1) * 255)\n", - " motor_angle, pendulum_angle = step(ser, act)\n", + " act = pendulum_PID(np.sin(pendulum_angle)) \n", + " if act != last_act:\n", + " last_act = act\n", + " act -= motor_pid(motor_angle)\n", + " act = np.clip(act, -1, 1)\n", + " nb_loops += 1\n", + " motor_angle, pendulum_angle = robot.step(act)\n", + "\n", + " actions.append(act)\n", + " motor_angles.append(motor_angle)\n", + " pendulum_angles.append(np.sin(pendulum_angle))\n", + " \n", + " if np.cos(pendulum_angle) > -0.5:\n", + " print(\"pendulum fell\")\n", + " break\n", + "\n", + "mean_loop_time = (time.time() - start) / nb_loops\n", + "print(int(1/mean_loop_time))\n", "\n", - " actions.append(act)\n", - " motor_angles.append(motor_angle)\n", - " pendulum_angles.append(np.sin(pendulum_angle))\n", - " \n", - " if np.cos(pendulum_angle) > -0.5:\n", - " print(\"pendulum fell\")\n", - " break\n", + "robot.close()\n", "\n", - "step(ser, 0)\n", - "ser.close()\n", "\n", "# plot actions, motor angles, pendulum angles\n", "plt.figure(1)\n", "plt.plot(actions)\n", + "plt.title(\"Actions\")\n", + "\n", "plt.figure(2)\n", - "plt.plot(pendulum_angles)" + "plt.plot(pendulum_angles)\n", + "plt.title(\"Pendulum Angles\")\n", + "\n", + "plt.figure(3)\n", + "plt.plot(motor_angles)\n", + "plt.title(\"Motor Angles\")" ] } ], diff --git a/poetry.lock b/poetry.lock index 388cd8c..5404f2e 100644 --- a/poetry.lock +++ b/poetry.lock @@ -365,6 +365,21 @@ files = [ {file = "distlib-0.3.7.tar.gz", hash = "sha256:9dafe54b34a028eafd95039d5e5d4851a13734540f1331060d31c9916e7147a8"}, ] +[[package]] +name = "exceptiongroup" +version = "1.2.0" +description = "Backport of PEP 654 (exception groups)" +category = "dev" +optional = false +python-versions = ">=3.7" +files = [ + {file = "exceptiongroup-1.2.0-py3-none-any.whl", hash = "sha256:4bfd3996ac73b41e9b9628b04e079f193850720ea5945fc96a08633c66912f14"}, + {file = "exceptiongroup-1.2.0.tar.gz", hash = "sha256:91f5c769735f051a4290d52edd0858999b57e5876e9f85937691bd4c9fa3ed68"}, +] + +[package.extras] +test = ["pytest (>=6)"] + [[package]] name = "executing" version = "2.0.1" @@ -561,6 +576,18 @@ zipp = {version = ">=3.1.0", markers = "python_version < \"3.10\""} docs = ["furo", "jaraco.packaging (>=9.3)", "jaraco.tidelift (>=1.4)", "rst.linker (>=1.9)", "sphinx (<7.2.5)", "sphinx (>=3.5)", "sphinx-lint"] testing = ["pytest (>=6)", "pytest-black (>=0.3.7)", "pytest-checkdocs (>=2.4)", "pytest-cov", "pytest-enabler (>=2.2)", "pytest-mypy (>=0.9.1)", "pytest-ruff", "zipp (>=3.17)"] +[[package]] +name = "iniconfig" +version = "2.0.0" +description = "brain-dead simple config-ini parsing" +category = "dev" +optional = false +python-versions = ">=3.7" +files = [ + {file = "iniconfig-2.0.0-py3-none-any.whl", hash = "sha256:b6a85871a79d2e3b22d2d1b94ac2824226a63c6b741c88f7ae975f18b6778374"}, + {file = "iniconfig-2.0.0.tar.gz", hash = "sha256:2d91e135bf72d31a410b17c16da610a82cb55f6b0477d1a902134b24a455b8b3"}, +] + [[package]] name = "ipykernel" version = "6.26.0" @@ -1103,6 +1130,22 @@ files = [ docs = ["furo (>=2023.7.26)", "proselint (>=0.13)", "sphinx (>=7.1.1)", "sphinx-autodoc-typehints (>=1.24)"] test = ["appdirs (==1.4.4)", "covdefaults (>=2.3)", "pytest (>=7.4)", "pytest-cov (>=4.1)", "pytest-mock (>=3.11.1)"] +[[package]] +name = "pluggy" +version = "1.3.0" +description = "plugin and hook calling mechanisms for python" +category = "dev" +optional = false +python-versions = ">=3.8" +files = [ + {file = "pluggy-1.3.0-py3-none-any.whl", hash = "sha256:d89c696a773f8bd377d18e5ecda92b7a3793cbe66c87060a6fb58c7b6e1061f7"}, + {file = "pluggy-1.3.0.tar.gz", hash = "sha256:cf61ae8f126ac6f7c451172cf30e3e43d3ca77615509771b3a984a0730651e12"}, +] + +[package.extras] +dev = ["pre-commit", "tox"] +testing = ["pytest", "pytest-benchmark"] + [[package]] name = "pre-commit" version = "3.5.0" @@ -1250,6 +1293,29 @@ files = [ [package.extras] cp2110 = ["hidapi"] +[[package]] +name = "pytest" +version = "7.4.4" +description = "pytest: simple powerful testing with Python" +category = "dev" +optional = false +python-versions = ">=3.7" +files = [ + {file = "pytest-7.4.4-py3-none-any.whl", hash = "sha256:b090cdf5ed60bf4c45261be03239c2c1c22df034fbffe691abe93cd80cea01d8"}, + {file = "pytest-7.4.4.tar.gz", hash = "sha256:2cf0005922c6ace4a3e2ec8b4080eb0d9753fdc93107415332f50ce9e7994280"}, +] + +[package.dependencies] +colorama = {version = "*", markers = "sys_platform == \"win32\""} +exceptiongroup = {version = ">=1.0.0rc8", markers = "python_version < \"3.11\""} +iniconfig = "*" +packaging = "*" +pluggy = ">=0.12,<2.0" +tomli = {version = ">=1.0.0", markers = "python_version < \"3.11\""} + +[package.extras] +testing = ["argcomplete", "attrs (>=19.2.0)", "hypothesis (>=3.56)", "mock", "nose", "pygments (>=2.7.2)", "requests", "setuptools", "xmlschema"] + [[package]] name = "python-dateutil" version = "2.8.2" @@ -1657,4 +1723,4 @@ testing = ["big-O", "jaraco.functools", "jaraco.itertools", "more-itertools", "p [metadata] lock-version = "2.0" python-versions = "^3.8" -content-hash = "1d97a85325d37004e3103382b0726e6cbf1bd635092754d328b953b3ade90924" +content-hash = "7a66902cdbc87792136b16bced15762a8c29007b3f07af05192bbdad5d54f0cd" diff --git a/pyproject.toml b/pyproject.toml index 02bd61e..d2af5af 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -16,6 +16,9 @@ matplotlib = "3.7.3" pre-commit = "^3.5.0" +[tool.poetry.group.dev.dependencies] +pytest = "^7.4.4" + [build-system] requires = ["poetry-core"] build-backend = "poetry.core.masonry.api" diff --git a/robot/firmware/firmware.ino b/robot/firmware/firmware.ino index 51950a8..f389848 100644 --- a/robot/firmware/firmware.ino +++ b/robot/firmware/firmware.ino @@ -1,6 +1,11 @@ #include #include +// protocol def +const uint8_t PACKET_SIZE = 6; +const uint8_t RESET = 0; +const uint8_t STEP = 1; + // Pin definitions const uint8_t MOTOR_DRIVER = 0; // 0 = MC33926 const uint8_t MOTOR_IN1 = 1; // which way to go @@ -23,24 +28,13 @@ const float PENDULUM_ENCODER_CPR = 8192; Encoder motorEncoder(MOTOR_ENC_A, MOTOR_ENC_B); Encoder pendulumEncoder(PENDULUM_ENC_A, PENDULUM_ENC_B); +volatile unsigned long lastCommandReceived = 0; +const unsigned long COMMAND_TIMEOUT = 500; // ms -void processMotorCommand(int16_t motor_command) { - // clamp motor command between -255 and 255 - if (motor_command > 255) { - motor_command = 255; - } - else if (motor_command < -255) { - motor_command = -255; - } - - // TODO deadzone - uint8_t scale_motor_command = 0; - if (motor_command != 0){ - scale_motor_command = int(0.3 * 255 + 0.7 * abs(motor_command)); - } +void processMotorCommand(uint16_t motor_command, bool direction) { if (MOTOR_DRIVER == 0) { // MC33926 - if (motor_command > 0) { + if (direction) { digitalWrite(MOTOR_IN1, LOW); digitalWrite(MOTOR_IN2, HIGH); } @@ -48,16 +42,16 @@ void processMotorCommand(int16_t motor_command) { digitalWrite(MOTOR_IN1, HIGH); digitalWrite(MOTOR_IN2, LOW); } - analogWrite(MOTOR_D2, scale_motor_command); + analogWrite(MOTOR_D2, motor_command); } else if (MOTOR_DRIVER == 1) { // TB9051-FTG - if (motor_command > 0) { - analogWrite(PWM1, scale_motor_command); + if (direction) { + analogWrite(PWM1, motor_command); analogWrite(PWM2, 0); } else { analogWrite(PWM1, 0); - analogWrite(PWM2, scale_motor_command); + analogWrite(PWM2, motor_command); } } } @@ -74,40 +68,65 @@ void setup() { pinMode(PWM1, OUTPUT); pinMode(PWM2, OUTPUT); } - analogWriteResolution(8); + analogWriteResolution(16); // setup serial - Serial.begin(57600); + Serial.begin(921600); } void loop() { - // if at least two bytes (== one motor command) - // in the serial buffer - if (Serial.available() >= 2){ - // read the two bytes - uint8_t low_byte = Serial.read(); - uint8_t high_byte = Serial.read(); - // combine the two bytes to one int16_t - int16_t motor_command = (high_byte << 8) | low_byte; - // process the motor command - processMotorCommand(motor_command); - - // read the motor and pendulum encoder values - // convert to angles in radians - // and send them back as two floats - - // read the motor and pendulum encoder values - long motorEncoderValue = motorEncoder.read(); - long pendulumEncoderValue = pendulumEncoder.read(); - - // convert to angles in radians - float motorAngle = (2 * PI * motorEncoderValue) / MOTOR_ENCODER_CPR; - float pendulumAngle = (2 * PI * pendulumEncoderValue) / PENDULUM_ENCODER_CPR; - - // send them back as two floats - Serial.write((uint8_t*)&motorAngle, sizeof(motorAngle)); - Serial.write((uint8_t*)&pendulumAngle, sizeof(pendulumAngle)); + if (millis() - lastCommandReceived > COMMAND_TIMEOUT) { + processMotorCommand(0, true); // kill motor } + if (Serial.available() >= PACKET_SIZE) { + // check for start sequence + if(Serial.read() != 0x10){ + return; + } + if(Serial.read() != 0x02){ + return; + } + + lastCommandReceived = millis(); + + // valid packet, read the command type + uint8_t command = Serial.read(); + if (command == RESET) { + // reset encoders + motorEncoder.write(0); + pendulumEncoder.write(0); + processMotorCommand(0, true); // kill motor + // Discard unnecessary bytes from the serial buffer + for (int i = 0; i < (PACKET_SIZE - 3); i++) { + Serial.read(); + } + } + else if (command == STEP) { + // read the two bytes + bool direction = Serial.read(); + uint16_t motor_command; + Serial.readBytes((char*)&motor_command, sizeof(motor_command)); + + // process the motor command + processMotorCommand(motor_command, direction); + + // read the motor and pendulum encoder values + // convert to angles in radians + // and send them back as two floats + + // read the motor and pendulum encoder values + long motorEncoderValue = motorEncoder.read(); + long pendulumEncoderValue = pendulumEncoder.read(); + + // convert to angles in radians + float motorAngle = (2 * PI * motorEncoderValue) / MOTOR_ENCODER_CPR; + float pendulumAngle = (2 * PI * pendulumEncoderValue) / PENDULUM_ENCODER_CPR; + + // send them back as two floats + Serial.write((uint8_t*)&motorAngle, sizeof(motorAngle)); + Serial.write((uint8_t*)&pendulumAngle, sizeof(pendulumAngle)); + } + } } diff --git a/tests/interactive_robot_selftest.py b/tests/interactive_robot_selftest.py new file mode 100644 index 0000000..e158f97 --- /dev/null +++ b/tests/interactive_robot_selftest.py @@ -0,0 +1,74 @@ +import time + +from furuta_gym.robot import Robot # replace with your actual module and class + +# not using pytest here bc couldn't get user input during test session + + +def test_control_freq(device): + robot = Robot(device) + nb_iterations = 10_000 + start_time = time.time() + + for _ in range(nb_iterations): + robot.step(0) + + elapsed_time = time.time() - start_time + mean_loop_time = elapsed_time / nb_iterations + max_control_freq = round(1 / mean_loop_time) + print(mean_loop_time) + print("max_control_freq: ", max_control_freq) + robot.close() + assert max_control_freq > 100, "Control frequency weirdly low." + + +def test_motor_stop(device): + robot = Robot(device) # replace with your actual constructor if needed + robot.step(0.35) + + time.sleep(0.5) # wait for 500ms + + # Ask the user if the motor has stopped + user_response = input("Has the motor stopped? (yes/no): ") + robot.close() + assert user_response.lower() == "yes", "The motor did not stop after 500ms" + + +def test_motor_direction(device): + robot = Robot(device) + robot.step(0.35) + time.sleep(0.5) # wait for 500ms + + user_response = input("Was the motor spinning clockwise? (yes/no): ") + robot.close() + assert user_response.lower() == "yes", "Motor spinning backwards, swap motor wires." + + +def print_report(results): + for result in results: + print(result) + + +def run_tests(tests, device): + results = [] + + for test in tests: + try: + test(device) + results.append(f"{test.__name__}: OK") + except Exception as e: + results.append(f"{test.__name__}: FAIL\n{str(e)}") + + return results + + +if __name__ == "__main__": + device = input("Enter robot device (press enter for default: /dev/ttyACM0): ") + if device == "": + device = "/dev/ttyACM0" + + tests = [test_control_freq, test_motor_stop, test_motor_direction] + + results = run_tests(tests, device) + print() + print_report(results)