From b6bd798f9e8dea8a99e985b93334a91bb4dac852 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Tue, 18 Jun 2024 10:43:08 -0400 Subject: [PATCH] [wpilib] Pregenerate PWM motor controllers (#6742) Co-authored-by: Gold856 <117957790+Gold856@users.noreply.github.com> --- .github/workflows/pregenerate.yml | 2 + wpilibc/generate_pwm_motor_controllers.py | 101 ++++++++++ .../pwm_motor_controller.cpp.jinja | 20 ++ .../pwm_motor_controller.h.jinja | 43 +++++ .../main/native/cpp/motorcontrol/DMC60.cpp | 4 +- .../main/native/cpp/motorcontrol/Jaguar.cpp | 2 + .../native/cpp/motorcontrol/PWMSparkFlex.cpp | 10 +- .../native/cpp/motorcontrol/PWMSparkMax.cpp | 7 +- .../native/cpp/motorcontrol/PWMTalonFX.cpp | 7 +- .../native/cpp/motorcontrol/PWMTalonSRX.cpp | 7 +- .../main/native/cpp/motorcontrol/PWMVenom.cpp | 4 +- .../native/cpp/motorcontrol/PWMVictorSPX.cpp | 7 +- .../main/native/cpp/motorcontrol/SD540.cpp | 7 +- .../main/native/cpp/motorcontrol/Spark.cpp | 4 +- .../main/native/cpp/motorcontrol/Talon.cpp | 2 + .../main/native/cpp/motorcontrol/Victor.cpp | 2 + .../main/native/cpp/motorcontrol/VictorSP.cpp | 4 +- .../native/include/frc/motorcontrol/DMC60.h | 6 +- .../native/include/frc/motorcontrol/Jaguar.h | 16 +- .../include/frc/motorcontrol/PWMSparkFlex.h | 6 +- .../include/frc/motorcontrol/PWMSparkMax.h | 6 +- .../include/frc/motorcontrol/PWMTalonFX.h | 15 +- .../include/frc/motorcontrol/PWMTalonSRX.h | 15 +- .../include/frc/motorcontrol/PWMVenom.h | 9 +- .../include/frc/motorcontrol/PWMVictorSPX.h | 17 +- .../native/include/frc/motorcontrol/SD540.h | 43 +++++ .../native/include/frc/motorcontrol/Spark.h | 18 +- .../native/include/frc/motorcontrol/Talon.h | 43 +++++ .../native/include/frc/motorcontrol/Victor.h | 43 +++++ .../include/frc/motorcontrol/VictorSP.h | 12 +- .../native/include/frc/motorcontrol/SD540.h | 41 ----- .../native/include/frc/motorcontrol/Talon.h | 41 ----- .../native/include/frc/motorcontrol/Victor.h | 45 ----- wpilibj/generate_pwm_motor_controllers.py | 66 +++++++ .../generate/pwm_motor_controller.java.jinja | 48 +++++ .../src/generate/pwm_motor_controllers.json | 172 ++++++++++++++++++ .../wpi/first/wpilibj/motorcontrol/DMC60.java | 8 +- .../first/wpilibj/motorcontrol/Jaguar.java | 11 +- .../wpilibj/motorcontrol/PWMSparkFlex.java | 9 +- .../wpilibj/motorcontrol/PWMSparkMax.java | 9 +- .../wpilibj/motorcontrol/PWMTalonFX.java | 16 +- .../wpilibj/motorcontrol/PWMTalonSRX.java | 16 +- .../first/wpilibj/motorcontrol/PWMVenom.java | 13 +- .../wpilibj/motorcontrol/PWMVictorSPX.java | 10 +- .../wpi/first/wpilibj/motorcontrol/SD540.java | 16 +- .../wpi/first/wpilibj/motorcontrol/Spark.java | 10 +- .../wpi/first/wpilibj/motorcontrol/Talon.java | 13 +- .../first/wpilibj/motorcontrol/Victor.java | 21 +-- .../first/wpilibj/motorcontrol/VictorSP.java | 14 +- 49 files changed, 790 insertions(+), 271 deletions(-) create mode 100755 wpilibc/generate_pwm_motor_controllers.py create mode 100644 wpilibc/src/generate/main/native/cpp/motorcontroller/pwm_motor_controller.cpp.jinja create mode 100644 wpilibc/src/generate/main/native/include/frc/motorcontroller/pwm_motor_controller.h.jinja rename wpilibc/src/{ => generated}/main/native/cpp/motorcontrol/DMC60.cpp (77%) rename wpilibc/src/{ => generated}/main/native/cpp/motorcontrol/Jaguar.cpp (86%) rename wpilibc/src/{ => generated}/main/native/cpp/motorcontrol/PWMSparkFlex.cpp (55%) rename wpilibc/src/{ => generated}/main/native/cpp/motorcontrol/PWMSparkMax.cpp (66%) rename wpilibc/src/{ => generated}/main/native/cpp/motorcontrol/PWMTalonFX.cpp (66%) rename wpilibc/src/{ => generated}/main/native/cpp/motorcontrol/PWMTalonSRX.cpp (66%) rename wpilibc/src/{ => generated}/main/native/cpp/motorcontrol/PWMVenom.cpp (77%) rename wpilibc/src/{ => generated}/main/native/cpp/motorcontrol/PWMVictorSPX.cpp (66%) rename wpilibc/src/{ => generated}/main/native/cpp/motorcontrol/SD540.cpp (66%) rename wpilibc/src/{ => generated}/main/native/cpp/motorcontrol/Spark.cpp (77%) rename wpilibc/src/{ => generated}/main/native/cpp/motorcontrol/Talon.cpp (86%) rename wpilibc/src/{ => generated}/main/native/cpp/motorcontrol/Victor.cpp (86%) rename wpilibc/src/{ => generated}/main/native/cpp/motorcontrol/VictorSP.cpp (77%) rename wpilibc/src/{ => generated}/main/native/include/frc/motorcontrol/DMC60.h (86%) rename wpilibc/src/{ => generated}/main/native/include/frc/motorcontrol/Jaguar.h (64%) rename wpilibc/src/{ => generated}/main/native/include/frc/motorcontrol/PWMSparkFlex.h (86%) rename wpilibc/src/{ => generated}/main/native/include/frc/motorcontrol/PWMSparkMax.h (86%) rename wpilibc/src/{ => generated}/main/native/include/frc/motorcontrol/PWMTalonFX.h (66%) rename wpilibc/src/{ => generated}/main/native/include/frc/motorcontrol/PWMTalonSRX.h (66%) rename wpilibc/src/{ => generated}/main/native/include/frc/motorcontrol/PWMVenom.h (77%) rename wpilibc/src/{ => generated}/main/native/include/frc/motorcontrol/PWMVictorSPX.h (62%) create mode 100644 wpilibc/src/generated/main/native/include/frc/motorcontrol/SD540.h rename wpilibc/src/{ => generated}/main/native/include/frc/motorcontrol/Spark.h (62%) create mode 100644 wpilibc/src/generated/main/native/include/frc/motorcontrol/Talon.h create mode 100644 wpilibc/src/generated/main/native/include/frc/motorcontrol/Victor.h rename wpilibc/src/{ => generated}/main/native/include/frc/motorcontrol/VictorSP.h (73%) delete mode 100644 wpilibc/src/main/native/include/frc/motorcontrol/SD540.h delete mode 100644 wpilibc/src/main/native/include/frc/motorcontrol/Talon.h delete mode 100644 wpilibc/src/main/native/include/frc/motorcontrol/Victor.h create mode 100755 wpilibj/generate_pwm_motor_controllers.py create mode 100644 wpilibj/src/generate/pwm_motor_controller.java.jinja create mode 100644 wpilibj/src/generate/pwm_motor_controllers.json rename wpilibj/src/{ => generated}/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java (81%) rename wpilibj/src/{ => generated}/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java (84%) rename wpilibj/src/{ => generated}/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkFlex.java (83%) rename wpilibj/src/{ => generated}/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkMax.java (84%) rename wpilibj/src/{ => generated}/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonFX.java (77%) rename wpilibj/src/{ => generated}/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonSRX.java (77%) rename wpilibj/src/{ => generated}/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVenom.java (80%) rename wpilibj/src/{ => generated}/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVictorSPX.java (86%) rename wpilibj/src/{ => generated}/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java (77%) rename wpilibj/src/{ => generated}/main/java/edu/wpi/first/wpilibj/motorcontrol/Spark.java (84%) rename wpilibj/src/{ => generated}/main/java/edu/wpi/first/wpilibj/motorcontrol/Talon.java (82%) rename wpilibj/src/{ => generated}/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java (52%) rename wpilibj/src/{ => generated}/main/java/edu/wpi/first/wpilibj/motorcontrol/VictorSP.java (76%) diff --git a/.github/workflows/pregenerate.yml b/.github/workflows/pregenerate.yml index ef63fc78af..2f94cb7efd 100644 --- a/.github/workflows/pregenerate.yml +++ b/.github/workflows/pregenerate.yml @@ -34,6 +34,8 @@ jobs: run: ./wpimath/generate_numbers.py && ./wpimath/generate_quickbuf.py --quickbuf_plugin=protoc-gen-quickbuf-1.3.3-linux-x86_64.exe - name: Run HIDs run: ./wpilibj/generate_hids.py && ./wpilibc/generate_hids.py && ./wpilibNewCommands/generate_hids.py + - name: Run PWM Controllers + run: ./wpilibj/generate_pwm_motor_controllers.py && ./wpilibc/generate_pwm_motor_controllers.py - name: Add untracked files to index so they count as changes run: git add -A - name: Check output diff --git a/wpilibc/generate_pwm_motor_controllers.py b/wpilibc/generate_pwm_motor_controllers.py new file mode 100755 index 0000000000..84d32a7498 --- /dev/null +++ b/wpilibc/generate_pwm_motor_controllers.py @@ -0,0 +1,101 @@ +#!/usr/bin/env python3 + +# Copyright (c) FIRST and other WPILib contributors. +# Open Source Software; you can modify and/or share it under the terms of +# the WPILib BSD license file in the root directory of this project. +import argparse +import json +import sys +import os +from typing import Dict, Any +from pathlib import Path + +from jinja2 import Environment, FileSystemLoader +from jinja2.environment import Template + + +def render_template( + template: Template, output_dir: Path, filename: str, controller: Dict[str, Any] +): + output_dir.mkdir(parents=True, exist_ok=True) + + output_file = output_dir / filename + output_file.write_text(template.render(controller), encoding="utf-8") + + +def generate_cpp_headers( + output_root: Path, template_root: Path, pwm_motor_controllers: Dict[str, Any] +): + header_template_root = template_root / "main/native/include/frc/motorcontroller" + env = Environment( + loader=FileSystemLoader(header_template_root), + autoescape=False, + keep_trailing_newline=True, + ) + + root_path = output_root / "main/native/include/frc/motorcontrol" + template = env.get_template("pwm_motor_controller.h.jinja") + + for controller in pwm_motor_controllers: + controller_name = os.path.basename(f"{controller['name']}.h") + render_template(template, root_path, controller_name, controller) + + +def generate_cpp_sources(output_root, template_root, pwm_motor_controllers): + cpp_template_root = str(template_root / "main/native/cpp/motorcontroller") + env = Environment( + loader=FileSystemLoader(cpp_template_root), + autoescape=False, + keep_trailing_newline=True, + ) + + root_path = output_root / "main/native/cpp/motorcontrol" + template = env.get_template("pwm_motor_controller.cpp.jinja") + + for controller in pwm_motor_controllers: + controller_name = os.path.basename(f"{controller['name']}.cpp") + render_template(template, root_path, controller_name, controller) + + +def generate_pwm_motor_controllers( + output_root: Path, template_root: Path, schema_root: Path +): + with (schema_root / "pwm_motor_controllers.json").open(encoding="utf-8") as f: + controllers = json.load(f) + + generate_cpp_headers(output_root, template_root, controllers) + generate_cpp_sources(output_root, template_root, controllers) + + +def main(argv): + script_path = Path(__file__).resolve() + dirname = script_path.parent + + parser = argparse.ArgumentParser() + parser.add_argument( + "--output_directory", + help="Optional. If set, will output the generated files to this directory, otherwise it will use a path relative to the script", + default=dirname / "src/generated", + type=Path, + ) + parser.add_argument( + "--schema_root", + help="Optional. If set, will use this directory as the root for discovering the pwm controller schema", + default=dirname / "../wpilibj/src/generate", + type=Path, + ) + parser.add_argument( + "--template_root", + help="Optional. If set, will use this directory as the root for the jinja templates", + default=dirname / "src/generate", + type=Path, + ) + args = parser.parse_args(argv) + + generate_pwm_motor_controllers( + args.output_directory, args.template_root, args.schema_root + ) + + +if __name__ == "__main__": + main(sys.argv[1:]) diff --git a/wpilibc/src/generate/main/native/cpp/motorcontroller/pwm_motor_controller.cpp.jinja b/wpilibc/src/generate/main/native/cpp/motorcontroller/pwm_motor_controller.cpp.jinja new file mode 100644 index 0000000000..ef995546ac --- /dev/null +++ b/wpilibc/src/generate/main/native/cpp/motorcontroller/pwm_motor_controller.cpp.jinja @@ -0,0 +1,20 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + +#include "frc/motorcontrol/{{ name }}.h" + +#include + +using namespace frc; + +{{ name }}::{{ name }}(int channel) : PWMMotorController("{{ name }}", channel) { + m_pwm.SetBounds({{ pulse_width_ms.max }}_ms, {{ pulse_width_ms.deadbandMax }}_ms, {{ pulse_width_ms.center }}_ms, {{ pulse_width_ms.deadbandMin }}_ms, {{ pulse_width_ms.min }}_ms); + m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_{{ PeriodMultiplier | default("1", true)}}X); + m_pwm.SetSpeed(0.0); + m_pwm.SetZeroLatch(); + + HAL_Report(HALUsageReporting::kResourceType_{{ ResourceName }}, GetChannel() + 1); +} diff --git a/wpilibc/src/generate/main/native/include/frc/motorcontroller/pwm_motor_controller.h.jinja b/wpilibc/src/generate/main/native/include/frc/motorcontroller/pwm_motor_controller.h.jinja new file mode 100644 index 0000000000..d1daa25d60 --- /dev/null +++ b/wpilibc/src/generate/main/native/include/frc/motorcontroller/pwm_motor_controller.h.jinja @@ -0,0 +1,43 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + +#pragma once + +#include "frc/motorcontrol/PWMMotorController.h" + +namespace frc { + +/** + * {{ Manufacturer }} {{ DisplayName }} Motor Controller with PWM control. + * + * Note that the {{ DisplayName }} uses the following bounds for PWM values. These + * values should work reasonably well for most controllers, but if users + * experience issues such as asymmetric behavior around the deadband or + * inability to saturate the controller in either direction, calibration is + * recommended. The calibration procedure can be found in the {{ DisplayName }} User + * Manual available from {{ Manufacturer }}. + * + * \li {{ "{:.3f}".format(pulse_width_ms.max) }}ms = full "forward" + * \li {{ "{:.3f}".format(pulse_width_ms.deadbandMax) }}ms = the "high end" of the deadband range + * \li {{ "{:.3f}".format(pulse_width_ms.center) }}ms = center of the deadband range (off) + * \li {{ "{:.3f}".format(pulse_width_ms.deadbandMin) }}ms = the "low end" of the deadband range + * \li {{ "{:.3f}".format(pulse_width_ms.min) }}ms = full "reverse" + */ +class {{ name }} : public PWMMotorController { + public: + /** + * Constructor for a {{ DisplayName }} connected via PWM. + * + * @param channel The PWM channel that the {{ DisplayName }} is attached to. 0-9 are + * on-board, 10-19 are on the MXP port + */ + explicit {{ name }}(int channel); + + {{ name }}({{ name }}&&) = default; + {{ name }}& operator=({{ name }}&&) = default; +}; + +} // namespace frc diff --git a/wpilibc/src/main/native/cpp/motorcontrol/DMC60.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/DMC60.cpp similarity index 77% rename from wpilibc/src/main/native/cpp/motorcontrol/DMC60.cpp rename to wpilibc/src/generated/main/native/cpp/motorcontrol/DMC60.cpp index ec136987c8..72eac176fd 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/DMC60.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/DMC60.cpp @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #include "frc/motorcontrol/DMC60.h" #include @@ -9,7 +11,7 @@ using namespace frc; DMC60::DMC60(int channel) : PWMMotorController("DMC60", channel) { - m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.50_ms, 1.48_ms, 0.997_ms); + m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms); m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X); m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); diff --git a/wpilibc/src/main/native/cpp/motorcontrol/Jaguar.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/Jaguar.cpp similarity index 86% rename from wpilibc/src/main/native/cpp/motorcontrol/Jaguar.cpp rename to wpilibc/src/generated/main/native/cpp/motorcontrol/Jaguar.cpp index a152566685..348ff568df 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/Jaguar.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/Jaguar.cpp @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #include "frc/motorcontrol/Jaguar.h" #include diff --git a/wpilibc/src/main/native/cpp/motorcontrol/PWMSparkFlex.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMSparkFlex.cpp similarity index 55% rename from wpilibc/src/main/native/cpp/motorcontrol/PWMSparkFlex.cpp rename to wpilibc/src/generated/main/native/cpp/motorcontrol/PWMSparkFlex.cpp index 945a70e22e..500757ee35 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/PWMSparkFlex.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMSparkFlex.cpp @@ -2,19 +2,19 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #include "frc/motorcontrol/PWMSparkFlex.h" #include using namespace frc; -PWMSparkFlex::PWMSparkFlex(int channel) - : PWMMotorController("PWMSparkFlex", channel) { - m_pwm.SetBounds(2.003_ms, 1.55_ms, 1.50_ms, 1.46_ms, 0.999_ms); +PWMSparkFlex::PWMSparkFlex(int channel) : PWMMotorController("PWMSparkFlex", channel) { + m_pwm.SetBounds(2.003_ms, 1.55_ms, 1.5_ms, 1.46_ms, 0.999_ms); m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X); m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); - HAL_Report(HALUsageReporting::kResourceType_RevSparkFlexPWM, - GetChannel() + 1); + HAL_Report(HALUsageReporting::kResourceType_RevSparkFlexPWM, GetChannel() + 1); } diff --git a/wpilibc/src/main/native/cpp/motorcontrol/PWMSparkMax.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMSparkMax.cpp similarity index 66% rename from wpilibc/src/main/native/cpp/motorcontrol/PWMSparkMax.cpp rename to wpilibc/src/generated/main/native/cpp/motorcontrol/PWMSparkMax.cpp index 56c3a45473..870b568f16 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/PWMSparkMax.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMSparkMax.cpp @@ -2,15 +2,16 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #include "frc/motorcontrol/PWMSparkMax.h" #include using namespace frc; -PWMSparkMax::PWMSparkMax(int channel) - : PWMMotorController("PWMSparkMax", channel) { - m_pwm.SetBounds(2.003_ms, 1.55_ms, 1.50_ms, 1.46_ms, 0.999_ms); +PWMSparkMax::PWMSparkMax(int channel) : PWMMotorController("PWMSparkMax", channel) { + m_pwm.SetBounds(2.003_ms, 1.55_ms, 1.5_ms, 1.46_ms, 0.999_ms); m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X); m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); diff --git a/wpilibc/src/main/native/cpp/motorcontrol/PWMTalonFX.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMTalonFX.cpp similarity index 66% rename from wpilibc/src/main/native/cpp/motorcontrol/PWMTalonFX.cpp rename to wpilibc/src/generated/main/native/cpp/motorcontrol/PWMTalonFX.cpp index 51327b0050..d9cd881214 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/PWMTalonFX.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMTalonFX.cpp @@ -2,15 +2,16 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #include "frc/motorcontrol/PWMTalonFX.h" #include using namespace frc; -PWMTalonFX::PWMTalonFX(int channel) - : PWMMotorController("PWMTalonFX", channel) { - m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.50_ms, 1.48_ms, 0.997_ms); +PWMTalonFX::PWMTalonFX(int channel) : PWMMotorController("PWMTalonFX", channel) { + m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms); m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X); m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); diff --git a/wpilibc/src/main/native/cpp/motorcontrol/PWMTalonSRX.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMTalonSRX.cpp similarity index 66% rename from wpilibc/src/main/native/cpp/motorcontrol/PWMTalonSRX.cpp rename to wpilibc/src/generated/main/native/cpp/motorcontrol/PWMTalonSRX.cpp index ee579ed201..5df4050743 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/PWMTalonSRX.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMTalonSRX.cpp @@ -2,15 +2,16 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #include "frc/motorcontrol/PWMTalonSRX.h" #include using namespace frc; -PWMTalonSRX::PWMTalonSRX(int channel) - : PWMMotorController("PWMTalonSRX", channel) { - m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.50_ms, 1.48_ms, 0.997_ms); +PWMTalonSRX::PWMTalonSRX(int channel) : PWMMotorController("PWMTalonSRX", channel) { + m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms); m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X); m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); diff --git a/wpilibc/src/main/native/cpp/motorcontrol/PWMVenom.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMVenom.cpp similarity index 77% rename from wpilibc/src/main/native/cpp/motorcontrol/PWMVenom.cpp rename to wpilibc/src/generated/main/native/cpp/motorcontrol/PWMVenom.cpp index 24041c8c08..451e1f35e7 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/PWMVenom.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMVenom.cpp @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #include "frc/motorcontrol/PWMVenom.h" #include @@ -9,7 +11,7 @@ using namespace frc; PWMVenom::PWMVenom(int channel) : PWMMotorController("PWMVenom", channel) { - m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.50_ms, 1.48_ms, 0.997_ms); + m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms); m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X); m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); diff --git a/wpilibc/src/main/native/cpp/motorcontrol/PWMVictorSPX.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMVictorSPX.cpp similarity index 66% rename from wpilibc/src/main/native/cpp/motorcontrol/PWMVictorSPX.cpp rename to wpilibc/src/generated/main/native/cpp/motorcontrol/PWMVictorSPX.cpp index 4aeb399ade..c759808a9d 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/PWMVictorSPX.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMVictorSPX.cpp @@ -2,15 +2,16 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #include "frc/motorcontrol/PWMVictorSPX.h" #include using namespace frc; -PWMVictorSPX::PWMVictorSPX(int channel) - : PWMMotorController("PWMVictorSPX", channel) { - m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.50_ms, 1.48_ms, 0.997_ms); +PWMVictorSPX::PWMVictorSPX(int channel) : PWMMotorController("PWMVictorSPX", channel) { + m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms); m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X); m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); diff --git a/wpilibc/src/main/native/cpp/motorcontrol/SD540.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/SD540.cpp similarity index 66% rename from wpilibc/src/main/native/cpp/motorcontrol/SD540.cpp rename to wpilibc/src/generated/main/native/cpp/motorcontrol/SD540.cpp index 7b6b838c85..c39e77f63f 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/SD540.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/SD540.cpp @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #include "frc/motorcontrol/SD540.h" #include @@ -9,11 +11,10 @@ using namespace frc; SD540::SD540(int channel) : PWMMotorController("SD540", channel) { - m_pwm.SetBounds(2.05_ms, 1.55_ms, 1.50_ms, 1.44_ms, 0.94_ms); + m_pwm.SetBounds(2.05_ms, 1.55_ms, 1.5_ms, 1.44_ms, 0.94_ms); m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X); m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); - HAL_Report(HALUsageReporting::kResourceType_MindsensorsSD540, - GetChannel() + 1); + HAL_Report(HALUsageReporting::kResourceType_MindsensorsSD540, GetChannel() + 1); } diff --git a/wpilibc/src/main/native/cpp/motorcontrol/Spark.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/Spark.cpp similarity index 77% rename from wpilibc/src/main/native/cpp/motorcontrol/Spark.cpp rename to wpilibc/src/generated/main/native/cpp/motorcontrol/Spark.cpp index 05ecb89515..4f2e078722 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/Spark.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/Spark.cpp @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #include "frc/motorcontrol/Spark.h" #include @@ -9,7 +11,7 @@ using namespace frc; Spark::Spark(int channel) : PWMMotorController("Spark", channel) { - m_pwm.SetBounds(2.003_ms, 1.55_ms, 1.50_ms, 1.46_ms, 0.999_ms); + m_pwm.SetBounds(2.003_ms, 1.55_ms, 1.5_ms, 1.46_ms, 0.999_ms); m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X); m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); diff --git a/wpilibc/src/main/native/cpp/motorcontrol/Talon.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/Talon.cpp similarity index 86% rename from wpilibc/src/main/native/cpp/motorcontrol/Talon.cpp rename to wpilibc/src/generated/main/native/cpp/motorcontrol/Talon.cpp index 4994bafc9b..9e81d2885c 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/Talon.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/Talon.cpp @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #include "frc/motorcontrol/Talon.h" #include diff --git a/wpilibc/src/main/native/cpp/motorcontrol/Victor.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/Victor.cpp similarity index 86% rename from wpilibc/src/main/native/cpp/motorcontrol/Victor.cpp rename to wpilibc/src/generated/main/native/cpp/motorcontrol/Victor.cpp index a05900f5cd..7062518bef 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/Victor.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/Victor.cpp @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #include "frc/motorcontrol/Victor.h" #include diff --git a/wpilibc/src/main/native/cpp/motorcontrol/VictorSP.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/VictorSP.cpp similarity index 77% rename from wpilibc/src/main/native/cpp/motorcontrol/VictorSP.cpp rename to wpilibc/src/generated/main/native/cpp/motorcontrol/VictorSP.cpp index 27419fb3b1..f8bc126093 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/VictorSP.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/VictorSP.cpp @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #include "frc/motorcontrol/VictorSP.h" #include @@ -9,7 +11,7 @@ using namespace frc; VictorSP::VictorSP(int channel) : PWMMotorController("VictorSP", channel) { - m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.50_ms, 1.48_ms, 0.997_ms); + m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms); m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X); m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/DMC60.h b/wpilibc/src/generated/main/native/include/frc/motorcontrol/DMC60.h similarity index 86% rename from wpilibc/src/main/native/include/frc/motorcontrol/DMC60.h rename to wpilibc/src/generated/main/native/include/frc/motorcontrol/DMC60.h index f47826a698..e994dc86d2 100644 --- a/wpilibc/src/main/native/include/frc/motorcontrol/DMC60.h +++ b/wpilibc/src/generated/main/native/include/frc/motorcontrol/DMC60.h @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #pragma once #include "frc/motorcontrol/PWMMotorController.h" @@ -9,7 +11,7 @@ namespace frc { /** - * Digilent DMC 60 Motor %Controller. + * Digilent DMC 60 Motor Controller with PWM control. * * Note that the DMC 60 uses the following bounds for PWM values. These * values should work reasonably well for most controllers, but if users @@ -27,7 +29,7 @@ namespace frc { class DMC60 : public PWMMotorController { public: /** - * Constructor for a Digilent DMC 60. + * Constructor for a DMC 60 connected via PWM. * * @param channel The PWM channel that the DMC 60 is attached to. 0-9 are * on-board, 10-19 are on the MXP port diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/Jaguar.h b/wpilibc/src/generated/main/native/include/frc/motorcontrol/Jaguar.h similarity index 64% rename from wpilibc/src/main/native/include/frc/motorcontrol/Jaguar.h rename to wpilibc/src/generated/main/native/include/frc/motorcontrol/Jaguar.h index d25a457f78..513b4c43ef 100644 --- a/wpilibc/src/main/native/include/frc/motorcontrol/Jaguar.h +++ b/wpilibc/src/generated/main/native/include/frc/motorcontrol/Jaguar.h @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #pragma once #include "frc/motorcontrol/PWMMotorController.h" @@ -9,14 +11,14 @@ namespace frc { /** - * Luminary Micro / Vex Robotics Jaguar Motor %Controller with PWM control. + * Luminary Micro / Vex Robotics Jaguar Motor Controller with PWM control. * - * Note that the Jaguar uses the following bounds for PWM values. These values - * should work reasonably well for most controllers, but if users experience - * issues such as asymmetric behavior around the deadband or inability to - * saturate the controller in either direction, calibration is recommended. The - * calibration procedure can be found in the Jaguar User Manual available from - * Vex. + * Note that the Jaguar uses the following bounds for PWM values. These + * values should work reasonably well for most controllers, but if users + * experience issues such as asymmetric behavior around the deadband or + * inability to saturate the controller in either direction, calibration is + * recommended. The calibration procedure can be found in the Jaguar User + * Manual available from Luminary Micro / Vex Robotics. * * \li 2.310ms = full "forward" * \li 1.550ms = the "high end" of the deadband range diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/PWMSparkFlex.h b/wpilibc/src/generated/main/native/include/frc/motorcontrol/PWMSparkFlex.h similarity index 86% rename from wpilibc/src/main/native/include/frc/motorcontrol/PWMSparkFlex.h rename to wpilibc/src/generated/main/native/include/frc/motorcontrol/PWMSparkFlex.h index 3106921d13..18e79bb4bd 100644 --- a/wpilibc/src/main/native/include/frc/motorcontrol/PWMSparkFlex.h +++ b/wpilibc/src/generated/main/native/include/frc/motorcontrol/PWMSparkFlex.h @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #pragma once #include "frc/motorcontrol/PWMMotorController.h" @@ -9,7 +11,7 @@ namespace frc { /** - * REV Robotics SPARK Flex Motor %Controller. + * REV Robotics SPARK Flex Motor Controller with PWM control. * * Note that the SPARK Flex uses the following bounds for PWM values. These * values should work reasonably well for most controllers, but if users @@ -27,7 +29,7 @@ namespace frc { class PWMSparkFlex : public PWMMotorController { public: /** - * Constructor for a SPARK Flex. + * Constructor for a SPARK Flex connected via PWM. * * @param channel The PWM channel that the SPARK Flex is attached to. 0-9 are * on-board, 10-19 are on the MXP port diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/PWMSparkMax.h b/wpilibc/src/generated/main/native/include/frc/motorcontrol/PWMSparkMax.h similarity index 86% rename from wpilibc/src/main/native/include/frc/motorcontrol/PWMSparkMax.h rename to wpilibc/src/generated/main/native/include/frc/motorcontrol/PWMSparkMax.h index 45c7baebeb..cf67454728 100644 --- a/wpilibc/src/main/native/include/frc/motorcontrol/PWMSparkMax.h +++ b/wpilibc/src/generated/main/native/include/frc/motorcontrol/PWMSparkMax.h @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #pragma once #include "frc/motorcontrol/PWMMotorController.h" @@ -9,7 +11,7 @@ namespace frc { /** - * REV Robotics SPARK MAX Motor %Controller. + * REV Robotics SPARK MAX Motor Controller with PWM control. * * Note that the SPARK MAX uses the following bounds for PWM values. These * values should work reasonably well for most controllers, but if users @@ -27,7 +29,7 @@ namespace frc { class PWMSparkMax : public PWMMotorController { public: /** - * Constructor for a SPARK MAX. + * Constructor for a SPARK MAX connected via PWM. * * @param channel The PWM channel that the SPARK MAX is attached to. 0-9 are * on-board, 10-19 are on the MXP port diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/PWMTalonFX.h b/wpilibc/src/generated/main/native/include/frc/motorcontrol/PWMTalonFX.h similarity index 66% rename from wpilibc/src/main/native/include/frc/motorcontrol/PWMTalonFX.h rename to wpilibc/src/generated/main/native/include/frc/motorcontrol/PWMTalonFX.h index 29aada6505..aee21022bc 100644 --- a/wpilibc/src/main/native/include/frc/motorcontrol/PWMTalonFX.h +++ b/wpilibc/src/generated/main/native/include/frc/motorcontrol/PWMTalonFX.h @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #pragma once #include "frc/motorcontrol/PWMMotorController.h" @@ -9,15 +11,14 @@ namespace frc { /** - * Cross the Road Electronics (CTRE) %Talon FX Motor %Controller with PWM - * control. + * Cross the Road Electronics (CTRE) Talon FX Motor Controller with PWM control. * - * Note that the %Talon FX uses the following bounds for PWM values. These + * Note that the Talon FX uses the following bounds for PWM values. These * values should work reasonably well for most controllers, but if users * experience issues such as asymmetric behavior around the deadband or * inability to saturate the controller in either direction, calibration is - * recommended. The calibration procedure can be found in the %Talon FX User - * Manual available from Cross The Road Electronics. + * recommended. The calibration procedure can be found in the Talon FX User + * Manual available from Cross the Road Electronics (CTRE). * * \li 2.004ms = full "forward" * \li 1.520ms = the "high end" of the deadband range @@ -28,9 +29,9 @@ namespace frc { class PWMTalonFX : public PWMMotorController { public: /** - * Construct a %Talon FX connected via PWM. + * Constructor for a Talon FX connected via PWM. * - * @param channel The PWM channel that the %Talon FX is attached to. 0-9 are + * @param channel The PWM channel that the Talon FX is attached to. 0-9 are * on-board, 10-19 are on the MXP port */ explicit PWMTalonFX(int channel); diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/PWMTalonSRX.h b/wpilibc/src/generated/main/native/include/frc/motorcontrol/PWMTalonSRX.h similarity index 66% rename from wpilibc/src/main/native/include/frc/motorcontrol/PWMTalonSRX.h rename to wpilibc/src/generated/main/native/include/frc/motorcontrol/PWMTalonSRX.h index 9f9e38496f..d848121ec8 100644 --- a/wpilibc/src/main/native/include/frc/motorcontrol/PWMTalonSRX.h +++ b/wpilibc/src/generated/main/native/include/frc/motorcontrol/PWMTalonSRX.h @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #pragma once #include "frc/motorcontrol/PWMMotorController.h" @@ -9,15 +11,14 @@ namespace frc { /** - * Cross the Road Electronics (CTRE) %Talon SRX Motor %Controller with PWM - * control. + * Cross the Road Electronics (CTRE) Talon SRX Motor Controller with PWM control. * - * Note that the %Talon SRX uses the following bounds for PWM values. These + * Note that the Talon SRX uses the following bounds for PWM values. These * values should work reasonably well for most controllers, but if users * experience issues such as asymmetric behavior around the deadband or * inability to saturate the controller in either direction, calibration is - * recommended. The calibration procedure can be found in the %Talon SRX User - * Manual available from Cross The Road Electronics. + * recommended. The calibration procedure can be found in the Talon SRX User + * Manual available from Cross the Road Electronics (CTRE). * * \li 2.004ms = full "forward" * \li 1.520ms = the "high end" of the deadband range @@ -28,9 +29,9 @@ namespace frc { class PWMTalonSRX : public PWMMotorController { public: /** - * Construct a %Talon SRX connected via PWM. + * Constructor for a Talon SRX connected via PWM. * - * @param channel The PWM channel that the %Talon SRX is attached to. 0-9 are + * @param channel The PWM channel that the Talon SRX is attached to. 0-9 are * on-board, 10-19 are on the MXP port */ explicit PWMTalonSRX(int channel); diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/PWMVenom.h b/wpilibc/src/generated/main/native/include/frc/motorcontrol/PWMVenom.h similarity index 77% rename from wpilibc/src/main/native/include/frc/motorcontrol/PWMVenom.h rename to wpilibc/src/generated/main/native/include/frc/motorcontrol/PWMVenom.h index 1047e8e7fc..77abffdfdc 100644 --- a/wpilibc/src/main/native/include/frc/motorcontrol/PWMVenom.h +++ b/wpilibc/src/generated/main/native/include/frc/motorcontrol/PWMVenom.h @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #pragma once #include "frc/motorcontrol/PWMMotorController.h" @@ -9,13 +11,14 @@ namespace frc { /** - * Playing with Fusion Venom Smart Motor with PWM control. + * Playing with Fusion Venom Motor Controller with PWM control. * * Note that the Venom uses the following bounds for PWM values. These * values should work reasonably well for most controllers, but if users * experience issues such as asymmetric behavior around the deadband or * inability to saturate the controller in either direction, calibration is - * recommended. + * recommended. The calibration procedure can be found in the Venom User + * Manual available from Playing with Fusion. * * \li 2.004ms = full "forward" * \li 1.520ms = the "high end" of the deadband range @@ -26,7 +29,7 @@ namespace frc { class PWMVenom : public PWMMotorController { public: /** - * Construct a Venom connected via PWM. + * Constructor for a Venom connected via PWM. * * @param channel The PWM channel that the Venom is attached to. 0-9 are * on-board, 10-19 are on the MXP port diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/PWMVictorSPX.h b/wpilibc/src/generated/main/native/include/frc/motorcontrol/PWMVictorSPX.h similarity index 62% rename from wpilibc/src/main/native/include/frc/motorcontrol/PWMVictorSPX.h rename to wpilibc/src/generated/main/native/include/frc/motorcontrol/PWMVictorSPX.h index b6bb3241ca..b6db49b9a6 100644 --- a/wpilibc/src/main/native/include/frc/motorcontrol/PWMVictorSPX.h +++ b/wpilibc/src/generated/main/native/include/frc/motorcontrol/PWMVictorSPX.h @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #pragma once #include "frc/motorcontrol/PWMMotorController.h" @@ -9,15 +11,14 @@ namespace frc { /** - * Cross the Road Electronics (CTRE) %Victor SPX Motor %Controller with PWM - * control. + * Cross the Road Electronics (CTRE) Victor SPX Motor Controller with PWM control. * - * Note that the %Victor SPX uses the following bounds for PWM values. These + * Note that the Victor SPX uses the following bounds for PWM values. These * values should work reasonably well for most controllers, but if users * experience issues such as asymmetric behavior around the deadband or * inability to saturate the controller in either direction, calibration is - * recommended. The calibration procedure can be found in the %Victor SPX User - * Manual available from Cross The Road Electronics. + * recommended. The calibration procedure can be found in the Victor SPX User + * Manual available from Cross the Road Electronics (CTRE). * * \li 2.004ms = full "forward" * \li 1.520ms = the "high end" of the deadband range @@ -28,10 +29,10 @@ namespace frc { class PWMVictorSPX : public PWMMotorController { public: /** - * Construct a %Victor SPX connected via PWM. + * Constructor for a Victor SPX connected via PWM. * - * @param channel The PWM channel that the %Victor SPX is attached to. 0-9 - * are on-board, 10-19 are on the MXP port + * @param channel The PWM channel that the Victor SPX is attached to. 0-9 are + * on-board, 10-19 are on the MXP port */ explicit PWMVictorSPX(int channel); diff --git a/wpilibc/src/generated/main/native/include/frc/motorcontrol/SD540.h b/wpilibc/src/generated/main/native/include/frc/motorcontrol/SD540.h new file mode 100644 index 0000000000..5cbc4f9584 --- /dev/null +++ b/wpilibc/src/generated/main/native/include/frc/motorcontrol/SD540.h @@ -0,0 +1,43 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + +#pragma once + +#include "frc/motorcontrol/PWMMotorController.h" + +namespace frc { + +/** + * Mindsensors SD540 Motor Controller with PWM control. + * + * Note that the SD540 uses the following bounds for PWM values. These + * values should work reasonably well for most controllers, but if users + * experience issues such as asymmetric behavior around the deadband or + * inability to saturate the controller in either direction, calibration is + * recommended. The calibration procedure can be found in the SD540 User + * Manual available from Mindsensors. + * + * \li 2.050ms = full "forward" + * \li 1.550ms = the "high end" of the deadband range + * \li 1.500ms = center of the deadband range (off) + * \li 1.440ms = the "low end" of the deadband range + * \li 0.940ms = full "reverse" + */ +class SD540 : public PWMMotorController { + public: + /** + * Constructor for a SD540 connected via PWM. + * + * @param channel The PWM channel that the SD540 is attached to. 0-9 are + * on-board, 10-19 are on the MXP port + */ + explicit SD540(int channel); + + SD540(SD540&&) = default; + SD540& operator=(SD540&&) = default; +}; + +} // namespace frc diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/Spark.h b/wpilibc/src/generated/main/native/include/frc/motorcontrol/Spark.h similarity index 62% rename from wpilibc/src/main/native/include/frc/motorcontrol/Spark.h rename to wpilibc/src/generated/main/native/include/frc/motorcontrol/Spark.h index 6163234555..4aa9b44dec 100644 --- a/wpilibc/src/main/native/include/frc/motorcontrol/Spark.h +++ b/wpilibc/src/generated/main/native/include/frc/motorcontrol/Spark.h @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #pragma once #include "frc/motorcontrol/PWMMotorController.h" @@ -9,14 +11,14 @@ namespace frc { /** - * REV Robotics SPARK Motor %Controller. + * REV Robotics SPARK Motor Controller with PWM control. * - * Note that the SPARK uses the following bounds for PWM values. These values - * should work reasonably well for most controllers, but if users experience - * issues such as asymmetric behavior around the deadband or inability to - * saturate the controller in either direction, calibration is recommended. - * The calibration procedure can be found in the SPARK User Manual available - * from REV Robotics. + * Note that the SPARK uses the following bounds for PWM values. These + * values should work reasonably well for most controllers, but if users + * experience issues such as asymmetric behavior around the deadband or + * inability to saturate the controller in either direction, calibration is + * recommended. The calibration procedure can be found in the SPARK User + * Manual available from REV Robotics. * * \li 2.003ms = full "forward" * \li 1.550ms = the "high end" of the deadband range @@ -27,7 +29,7 @@ namespace frc { class Spark : public PWMMotorController { public: /** - * Constructor for a SPARK. + * Constructor for a SPARK connected via PWM. * * @param channel The PWM channel that the SPARK is attached to. 0-9 are * on-board, 10-19 are on the MXP port diff --git a/wpilibc/src/generated/main/native/include/frc/motorcontrol/Talon.h b/wpilibc/src/generated/main/native/include/frc/motorcontrol/Talon.h new file mode 100644 index 0000000000..a7db150a41 --- /dev/null +++ b/wpilibc/src/generated/main/native/include/frc/motorcontrol/Talon.h @@ -0,0 +1,43 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + +#pragma once + +#include "frc/motorcontrol/PWMMotorController.h" + +namespace frc { + +/** + * Cross the Road Electronics (CTRE) Talon Motor Controller with PWM control. + * + * Note that the Talon uses the following bounds for PWM values. These + * values should work reasonably well for most controllers, but if users + * experience issues such as asymmetric behavior around the deadband or + * inability to saturate the controller in either direction, calibration is + * recommended. The calibration procedure can be found in the Talon User + * Manual available from Cross the Road Electronics (CTRE). + * + * \li 2.037ms = full "forward" + * \li 1.539ms = the "high end" of the deadband range + * \li 1.513ms = center of the deadband range (off) + * \li 1.487ms = the "low end" of the deadband range + * \li 0.989ms = full "reverse" + */ +class Talon : public PWMMotorController { + public: + /** + * Constructor for a Talon connected via PWM. + * + * @param channel The PWM channel that the Talon is attached to. 0-9 are + * on-board, 10-19 are on the MXP port + */ + explicit Talon(int channel); + + Talon(Talon&&) = default; + Talon& operator=(Talon&&) = default; +}; + +} // namespace frc diff --git a/wpilibc/src/generated/main/native/include/frc/motorcontrol/Victor.h b/wpilibc/src/generated/main/native/include/frc/motorcontrol/Victor.h new file mode 100644 index 0000000000..95d6ed0fc3 --- /dev/null +++ b/wpilibc/src/generated/main/native/include/frc/motorcontrol/Victor.h @@ -0,0 +1,43 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + +#pragma once + +#include "frc/motorcontrol/PWMMotorController.h" + +namespace frc { + +/** + * Vex Robotics Victor 888 Motor Controller with PWM control. + * + * Note that the Victor 888 uses the following bounds for PWM values. These + * values should work reasonably well for most controllers, but if users + * experience issues such as asymmetric behavior around the deadband or + * inability to saturate the controller in either direction, calibration is + * recommended. The calibration procedure can be found in the Victor 888 User + * Manual available from Vex Robotics. + * + * \li 2.027ms = full "forward" + * \li 1.525ms = the "high end" of the deadband range + * \li 1.507ms = center of the deadband range (off) + * \li 1.490ms = the "low end" of the deadband range + * \li 1.026ms = full "reverse" + */ +class Victor : public PWMMotorController { + public: + /** + * Constructor for a Victor 888 connected via PWM. + * + * @param channel The PWM channel that the Victor 888 is attached to. 0-9 are + * on-board, 10-19 are on the MXP port + */ + explicit Victor(int channel); + + Victor(Victor&&) = default; + Victor& operator=(Victor&&) = default; +}; + +} // namespace frc diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/VictorSP.h b/wpilibc/src/generated/main/native/include/frc/motorcontrol/VictorSP.h similarity index 73% rename from wpilibc/src/main/native/include/frc/motorcontrol/VictorSP.h rename to wpilibc/src/generated/main/native/include/frc/motorcontrol/VictorSP.h index f599ff4dda..d1a74d60a2 100644 --- a/wpilibc/src/main/native/include/frc/motorcontrol/VictorSP.h +++ b/wpilibc/src/generated/main/native/include/frc/motorcontrol/VictorSP.h @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY + #pragma once #include "frc/motorcontrol/PWMMotorController.h" @@ -9,14 +11,14 @@ namespace frc { /** - * Vex Robotics %Victor SP Motor %Controller. + * Vex Robotics Victor SP Motor Controller with PWM control. * - * Note that the %Victor SP uses the following bounds for PWM values. These + * Note that the Victor SP uses the following bounds for PWM values. These * values should work reasonably well for most controllers, but if users * experience issues such as asymmetric behavior around the deadband or * inability to saturate the controller in either direction, calibration is - * recommended. The calibration procedure can be found in the %Victor SP User - * Manual available from Vex. + * recommended. The calibration procedure can be found in the Victor SP User + * Manual available from Vex Robotics. * * \li 2.004ms = full "forward" * \li 1.520ms = the "high end" of the deadband range @@ -27,7 +29,7 @@ namespace frc { class VictorSP : public PWMMotorController { public: /** - * Constructor for a %Victor SP. + * Constructor for a Victor SP connected via PWM. * * @param channel The PWM channel that the Victor SP is attached to. 0-9 are * on-board, 10-19 are on the MXP port diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/SD540.h b/wpilibc/src/main/native/include/frc/motorcontrol/SD540.h deleted file mode 100644 index 44a0c8cc08..0000000000 --- a/wpilibc/src/main/native/include/frc/motorcontrol/SD540.h +++ /dev/null @@ -1,41 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#pragma once - -#include "frc/motorcontrol/PWMMotorController.h" - -namespace frc { - -/** - * Mindsensors SD540 Motor %Controller. - * - * Note that the SD540 uses the following bounds for PWM values. These values - * should work reasonably well for most controllers, but if users experience - * issues such as asymmetric behavior around the deadband or inability to - * saturate the controller in either direction, calibration is recommended. - * The calibration procedure can be found in the SD540 User Manual available - * from Mindsensors. - * - * \li 2.05ms = full "forward" - * \li 1.55ms = the "high end" of the deadband range - * \li 1.50ms = center of the deadband range (off) - * \li 1.44ms = the "low end" of the deadband range - * \li 0.94ms = full "reverse" - */ -class SD540 : public PWMMotorController { - public: - /** - * Constructor for a SD540. - * - * @param channel The PWM channel that the SD540 is attached to. 0-9 are - * on-board, 10-19 are on the MXP port - */ - explicit SD540(int channel); - - SD540(SD540&&) = default; - SD540& operator=(SD540&&) = default; -}; - -} // namespace frc diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/Talon.h b/wpilibc/src/main/native/include/frc/motorcontrol/Talon.h deleted file mode 100644 index acf5c554f8..0000000000 --- a/wpilibc/src/main/native/include/frc/motorcontrol/Talon.h +++ /dev/null @@ -1,41 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#pragma once - -#include "frc/motorcontrol/PWMMotorController.h" - -namespace frc { - -/** - * Cross the Road Electronics (CTRE) %Talon and %Talon SR Motor %Controller. - * - * Note that the %Talon uses the following bounds for PWM values. These values - * should work reasonably well for most controllers, but if users experience - * issues such as asymmetric behavior around the deadband or inability to - * saturate the controller in either direction, calibration is recommended. - * The calibration procedure can be found in the %Talon User Manual available - * from CTRE. - * - * \li 2.037ms = full "forward" - * \li 1.539ms = the "high end" of the deadband range - * \li 1.513ms = center of the deadband range (off) - * \li 1.487ms = the "low end" of the deadband range - * \li 0.989ms = full "reverse" - */ -class Talon : public PWMMotorController { - public: - /** - * Constructor for a %Talon (original or %Talon SR). - * - * @param channel The PWM channel number that the %Talon is attached to. 0-9 - * are on-board, 10-19 are on the MXP port - */ - explicit Talon(int channel); - - Talon(Talon&&) = default; - Talon& operator=(Talon&&) = default; -}; - -} // namespace frc diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/Victor.h b/wpilibc/src/main/native/include/frc/motorcontrol/Victor.h deleted file mode 100644 index 96279250d0..0000000000 --- a/wpilibc/src/main/native/include/frc/motorcontrol/Victor.h +++ /dev/null @@ -1,45 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#pragma once - -#include "frc/motorcontrol/PWMMotorController.h" - -namespace frc { - -/** - * Vex Robotics %Victor 888 Motor %Controller. - * - * The Vex Robotics %Victor 884 Motor %Controller can also be used with this - * class but may need to be calibrated per the Victor 884 user manual. - * - * Note that the %Victor uses the following bounds for PWM values. These - * values were determined empirically and optimized for the %Victor 888. These - * values should work reasonably well for %Victor 884 controllers as well but - * if users experience issues such as asymmetric behavior around the deadband - * or inability to saturate the controller in either direction, calibration is - * recommended. The calibration procedure can be found in the %Victor 884 User - * Manual available from Vex. - * - * \li 2.027ms = full "forward" - * \li 1.525ms = the "high end" of the deadband range - * \li 1.507ms = center of the deadband range (off) - * \li 1.490ms = the "low end" of the deadband range - * \li 1.026ms = full "reverse" - */ -class Victor : public PWMMotorController { - public: - /** - * Constructor for a %Victor. - * - * @param channel The PWM channel number that the %Victor is attached to. 0-9 - * are on-board, 10-19 are on the MXP port - */ - explicit Victor(int channel); - - Victor(Victor&&) = default; - Victor& operator=(Victor&&) = default; -}; - -} // namespace frc diff --git a/wpilibj/generate_pwm_motor_controllers.py b/wpilibj/generate_pwm_motor_controllers.py new file mode 100755 index 0000000000..1c1be7201f --- /dev/null +++ b/wpilibj/generate_pwm_motor_controllers.py @@ -0,0 +1,66 @@ +#!/usr/bin/env python3 + +# Copyright (c) FIRST and other WPILib contributors. +# Open Source Software; you can modify and/or share it under the terms of +# the WPILib BSD license file in the root directory of this project. +import argparse +import json +import sys +from pathlib import Path +from typing import Dict, Any + +from jinja2 import Environment, FileSystemLoader +from jinja2.environment import Template + + +def render_template( + template: Template, output_dir: Path, filename: str, controller: Dict[str, Any] +): + output_dir.mkdir(parents=True, exist_ok=True) + + output_file = output_dir / filename + output_file.write_text(template.render(controller), encoding="utf-8") + + +def generate_pwm_motor_controllers(output_root, template_root): + with (template_root / "pwm_motor_controllers.json").open(encoding="utf-8") as f: + controllers = json.load(f) + + env = Environment( + loader=FileSystemLoader(str(template_root)), + autoescape=False, + keep_trailing_newline=True, + ) + + root_path = Path(output_root) / "main/java/edu/wpi/first/wpilibj/motorcontrol" + template = env.get_template("pwm_motor_controller.java.jinja") + + for controller in controllers: + controller_name = f"{controller['name']}.java" + render_template(template, root_path, controller_name, controller) + + +def main(argv): + script_path = Path(__file__).resolve() + dirname = script_path.parent + + parser = argparse.ArgumentParser() + parser.add_argument( + "--output_directory", + help="Optional. If set, will output the generated files to this directory, otherwise it will use a path relative to the script", + default=dirname / "src/generated", + type=Path, + ) + parser.add_argument( + "--template_root", + help="Optional. If set, will use this directory as the root for the jinja templates", + default=dirname / "src/generate", + type=Path, + ) + args = parser.parse_args(argv) + + generate_pwm_motor_controllers(args.output_directory, args.template_root) + + +if __name__ == "__main__": + main(sys.argv[1:]) diff --git a/wpilibj/src/generate/pwm_motor_controller.java.jinja b/wpilibj/src/generate/pwm_motor_controller.java.jinja new file mode 100644 index 0000000000..a95145df39 --- /dev/null +++ b/wpilibj/src/generate/pwm_motor_controller.java.jinja @@ -0,0 +1,48 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY + +package edu.wpi.first.wpilibj.motorcontrol; + +import edu.wpi.first.hal.FRCNetComm.tResourceType; +import edu.wpi.first.hal.HAL; +import edu.wpi.first.wpilibj.PWM; + +/** + * {{ Manufacturer }} {{ DisplayName }} Motor Controller. + * + *

Note that the {{ DisplayName }} uses the following bounds for PWM values. These values should work + * reasonably well for most controllers, but if users experience issues such as asymmetric behavior + * around the deadband or inability to saturate the controller in either direction, calibration is + * recommended. The calibration procedure can be found in the {{ DisplayName }} User Manual available from + * {{ Manufacturer }}. + * + *

    + *
  • {{ "{:.3f}".format(pulse_width_ms.max) }}ms = full "forward" + *
  • {{ "{:.3f}".format(pulse_width_ms.deadbandMax) }}ms = the "high end" of the deadband range + *
  • {{ "{:.3f}".format(pulse_width_ms.center) }}ms = center of the deadband range (off) + *
  • {{ "{:.3f}".format(pulse_width_ms.deadbandMin) }}ms = the "low end" of the deadband range + *
  • {{ "{:.3f}".format(pulse_width_ms.min) }}ms = full "reverse" + *
+ */ +public class {{ name }} extends PWMMotorController { + /** + * Constructor. + * + * @param channel The PWM channel that the {{ DisplayName }} is attached to. 0-9 are on-board, 10-19 + * are on the MXP port + */ + @SuppressWarnings("this-escape") + public {{ name }}(final int channel) { + super("{{ name }}", channel); + + m_pwm.setBoundsMicroseconds({{ (pulse_width_ms.max * 1000) | int }}, {{ (pulse_width_ms.deadbandMax * 1000) | int }}, {{ (pulse_width_ms.center * 1000) | int }}, {{ (pulse_width_ms.deadbandMin * 1000) | int }}, {{ (pulse_width_ms.min * 1000) | int }}); + m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k{{ PeriodMultiplier | default("1", true)}}X); + m_pwm.setSpeed(0.0); + m_pwm.setZeroLatch(); + + HAL.report(tResourceType.kResourceType_{{ ResourceName }}, getChannel() + 1); + } +} diff --git a/wpilibj/src/generate/pwm_motor_controllers.json b/wpilibj/src/generate/pwm_motor_controllers.json new file mode 100644 index 0000000000..a2c9feab0c --- /dev/null +++ b/wpilibj/src/generate/pwm_motor_controllers.json @@ -0,0 +1,172 @@ +[ + { + "name": "DMC60", + "Manufacturer": "Digilent", + "DisplayName": "DMC 60", + "ResourceName": "DigilentDMC60", + "pulse_width_ms": { + "max": 2.004, + "deadbandMax": 1.520, + "center": 1.500, + "deadbandMin": 1.480, + "min": 0.997 + } + }, + { + "name": "Jaguar", + "Manufacturer": "Luminary Micro / Vex Robotics", + "DisplayName": "Jaguar", + "ResourceName": "Jaguar", + "pulse_width_ms": { + "max": 2.310, + "deadbandMax": 1.550, + "center": 1.507, + "deadbandMin": 1.454, + "min": 0.697 + } + }, + { + "name": "PWMSparkFlex", + "Manufacturer": "REV Robotics", + "DisplayName": "SPARK Flex", + "ResourceName": "RevSparkFlexPWM", + "pulse_width_ms": { + "max": 2.003, + "deadbandMax": 1.550, + "center": 1.500, + "deadbandMin": 1.460, + "min": 0.999 + } + }, + { + "name": "PWMSparkMax", + "Manufacturer": "REV Robotics", + "DisplayName": "SPARK MAX", + "ResourceName": "RevSparkMaxPWM", + "pulse_width_ms": { + "max": 2.003, + "deadbandMax": 1.550, + "center": 1.500, + "deadbandMin": 1.460, + "min": 0.999 + } + }, + { + "name": "PWMTalonFX", + "Manufacturer": "Cross the Road Electronics (CTRE)", + "DisplayName": "Talon FX", + "ResourceName": "TalonFX", + "pulse_width_ms": { + "max": 2.004, + "deadbandMax": 1.520, + "center": 1.500, + "deadbandMin": 1.480, + "min": 0.997 + } + }, + { + "name": "PWMTalonSRX", + "Manufacturer": "Cross the Road Electronics (CTRE)", + "DisplayName": "Talon SRX", + "ResourceName": "PWMTalonSRX", + "pulse_width_ms": { + "max": 2.004, + "deadbandMax": 1.520, + "center": 1.500, + "deadbandMin": 1.480, + "min": 0.997 + } + }, + { + "name": "PWMVenom", + "Manufacturer": "Playing with Fusion", + "DisplayName": "Venom", + "ResourceName": "FusionVenom", + "pulse_width_ms": { + "max": 2.004, + "deadbandMax": 1.520, + "center": 1.500, + "deadbandMin": 1.480, + "min": 0.997 + } + }, + { + "name": "PWMVictorSPX", + "Manufacturer": "Cross the Road Electronics (CTRE)", + "DisplayName": "Victor SPX", + "ResourceName": "PWMVictorSPX", + "pulse_width_ms": { + "max": 2.004, + "deadbandMax": 1.520, + "center": 1.500, + "deadbandMin": 1.480, + "min": 0.997 + } + }, + { + "name": "SD540", + "Manufacturer": "Mindsensors", + "DisplayName": "SD540", + "ResourceName": "MindsensorsSD540", + "pulse_width_ms": { + "max": 2.05, + "deadbandMax": 1.55, + "center": 1.50, + "deadbandMin": 1.44, + "min": 0.94 + } + }, + { + "name": "Spark", + "Manufacturer": "REV Robotics", + "DisplayName": "SPARK", + "ResourceName": "RevSPARK", + "pulse_width_ms": { + "max": 2.003, + "deadbandMax": 1.550, + "center": 1.500, + "deadbandMin": 1.460, + "min": 0.999 + } + }, + { + "name": "Talon", + "Manufacturer": "Cross the Road Electronics (CTRE)", + "DisplayName": "Talon", + "ResourceName": "Talon", + "pulse_width_ms": { + "max": 2.037, + "deadbandMax": 1.539, + "center": 1.513, + "deadbandMin": 1.487, + "min": 0.989 + } + }, + { + "name": "Victor", + "Manufacturer": "Vex Robotics", + "DisplayName": "Victor 888", + "ResourceName": "Victor", + "PeriodMultiplier": 2, + "pulse_width_ms": { + "max": 2.027, + "deadbandMax": 1.525, + "center": 1.507, + "deadbandMin": 1.490, + "min": 1.026 + } + }, + { + "name": "VictorSP", + "Manufacturer": "Vex Robotics", + "DisplayName": "Victor SP", + "ResourceName": "VictorSP", + "pulse_width_ms": { + "max": 2.004, + "deadbandMax": 1.520, + "center": 1.500, + "deadbandMin": 1.480, + "min": 0.997 + } + } +] diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java similarity index 81% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java rename to wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java index 9d669078bd..25e11c159b 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY + package edu.wpi.first.wpilibj.motorcontrol; import edu.wpi.first.hal.FRCNetComm.tResourceType; @@ -11,7 +13,7 @@ import edu.wpi.first.wpilibj.PWM; /** * Digilent DMC 60 Motor Controller. * - *

Note that the DMC uses the following bounds for PWM values. These values should work + *

Note that the DMC 60 uses the following bounds for PWM values. These values should work * reasonably well for most controllers, but if users experience issues such as asymmetric behavior * around the deadband or inability to saturate the controller in either direction, calibration is * recommended. The calibration procedure can be found in the DMC 60 User Manual available from @@ -29,8 +31,8 @@ public class DMC60 extends PWMMotorController { /** * Constructor. * - * @param channel The PWM channel that the DMC60 is attached to. 0-9 are on-board, 10-19 are on - * the MXP port + * @param channel The PWM channel that the DMC 60 is attached to. 0-9 are on-board, 10-19 + * are on the MXP port */ @SuppressWarnings("this-escape") public DMC60(final int channel) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java similarity index 84% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java rename to wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java index 4a0ac85572..d9638942a3 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY + package edu.wpi.first.wpilibj.motorcontrol; import edu.wpi.first.hal.FRCNetComm.tResourceType; @@ -9,12 +11,13 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; /** - * Texas Instruments / Vex Robotics Jaguar Motor Controller as a PWM device. + * Luminary Micro / Vex Robotics Jaguar Motor Controller. * *

Note that the Jaguar uses the following bounds for PWM values. These values should work * reasonably well for most controllers, but if users experience issues such as asymmetric behavior * around the deadband or inability to saturate the controller in either direction, calibration is - * recommended. The calibration procedure can be found in the Jaguar User Manual available from Vex. + * recommended. The calibration procedure can be found in the Jaguar User Manual available from + * Luminary Micro / Vex Robotics. * *

    *
  • 2.310ms = full "forward" @@ -28,8 +31,8 @@ public class Jaguar extends PWMMotorController { /** * Constructor. * - * @param channel The PWM channel that the Jaguar is attached to. 0-9 are on-board, 10-19 are on - * the MXP port + * @param channel The PWM channel that the Jaguar is attached to. 0-9 are on-board, 10-19 + * are on the MXP port */ @SuppressWarnings("this-escape") public Jaguar(final int channel) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkFlex.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkFlex.java similarity index 83% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkFlex.java rename to wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkFlex.java index 059b18af1d..e507efe3de 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkFlex.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkFlex.java @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY + package edu.wpi.first.wpilibj.motorcontrol; import edu.wpi.first.hal.FRCNetComm.tResourceType; @@ -9,7 +11,7 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; /** - * REV Robotics SPARK Flex Motor Controller with PWM control. + * REV Robotics SPARK Flex Motor Controller. * *

    Note that the SPARK Flex uses the following bounds for PWM values. These values should work * reasonably well for most controllers, but if users experience issues such as asymmetric behavior @@ -27,9 +29,10 @@ import edu.wpi.first.wpilibj.PWM; */ public class PWMSparkFlex extends PWMMotorController { /** - * Common initialization code called by all constructors. + * Constructor. * - * @param channel The PWM channel number. 0-9 are on-board, 10-19 are on the MXP port + * @param channel The PWM channel that the SPARK Flex is attached to. 0-9 are on-board, 10-19 + * are on the MXP port */ @SuppressWarnings("this-escape") public PWMSparkFlex(final int channel) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkMax.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkMax.java similarity index 84% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkMax.java rename to wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkMax.java index 205d70a0de..88dd49aa93 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkMax.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkMax.java @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY + package edu.wpi.first.wpilibj.motorcontrol; import edu.wpi.first.hal.FRCNetComm.tResourceType; @@ -9,7 +11,7 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; /** - * REV Robotics SPARK MAX Motor Controller with PWM control. + * REV Robotics SPARK MAX Motor Controller. * *

    Note that the SPARK MAX uses the following bounds for PWM values. These values should work * reasonably well for most controllers, but if users experience issues such as asymmetric behavior @@ -27,9 +29,10 @@ import edu.wpi.first.wpilibj.PWM; */ public class PWMSparkMax extends PWMMotorController { /** - * Common initialization code called by all constructors. + * Constructor. * - * @param channel The PWM channel number. 0-9 are on-board, 10-19 are on the MXP port + * @param channel The PWM channel that the SPARK MAX is attached to. 0-9 are on-board, 10-19 + * are on the MXP port */ @SuppressWarnings("this-escape") public PWMSparkMax(final int channel) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonFX.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonFX.java similarity index 77% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonFX.java rename to wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonFX.java index 2211fa5269..7b5b020464 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonFX.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonFX.java @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY + package edu.wpi.first.wpilibj.motorcontrol; import edu.wpi.first.hal.FRCNetComm.tResourceType; @@ -9,13 +11,13 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; /** - * Cross the Road Electronics (CTRE) Talon FX Motor Controller with PWM control. + * Cross the Road Electronics (CTRE) Talon FX Motor Controller. * - *

    Note that the TalonFX uses the following bounds for PWM values. These values should work + *

    Note that the Talon FX uses the following bounds for PWM values. These values should work * reasonably well for most controllers, but if users experience issues such as asymmetric behavior * around the deadband or inability to saturate the controller in either direction, calibration is - * recommended. The calibration procedure can be found in the TalonFX User Manual available from - * CTRE. + * recommended. The calibration procedure can be found in the Talon FX User Manual available from + * Cross the Road Electronics (CTRE). * *

      *
    • 2.004ms = full "forward" @@ -27,10 +29,10 @@ import edu.wpi.first.wpilibj.PWM; */ public class PWMTalonFX extends PWMMotorController { /** - * Constructor for a TalonFX connected via PWM. + * Constructor. * - * @param channel The PWM channel that the Talon FX is attached to. 0-9 are on-board, 10-19 are on - * the MXP port + * @param channel The PWM channel that the Talon FX is attached to. 0-9 are on-board, 10-19 + * are on the MXP port */ @SuppressWarnings("this-escape") public PWMTalonFX(final int channel) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonSRX.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonSRX.java similarity index 77% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonSRX.java rename to wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonSRX.java index 4677627f23..21061f4191 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonSRX.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonSRX.java @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY + package edu.wpi.first.wpilibj.motorcontrol; import edu.wpi.first.hal.FRCNetComm.tResourceType; @@ -9,13 +11,13 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; /** - * Cross the Road Electronics (CTRE) Talon SRX Motor Controller with PWM control. + * Cross the Road Electronics (CTRE) Talon SRX Motor Controller. * - *

      Note that the TalonSRX uses the following bounds for PWM values. These values should work + *

      Note that the Talon SRX uses the following bounds for PWM values. These values should work * reasonably well for most controllers, but if users experience issues such as asymmetric behavior * around the deadband or inability to saturate the controller in either direction, calibration is - * recommended. The calibration procedure can be found in the TalonSRX User Manual available from - * CTRE. + * recommended. The calibration procedure can be found in the Talon SRX User Manual available from + * Cross the Road Electronics (CTRE). * *

        *
      • 2.004ms = full "forward" @@ -27,10 +29,10 @@ import edu.wpi.first.wpilibj.PWM; */ public class PWMTalonSRX extends PWMMotorController { /** - * Constructor for a TalonSRX connected via PWM. + * Constructor. * - * @param channel The PWM channel that the Talon SRX is attached to. 0-9 are on-board, 10-19 are - * on the MXP port + * @param channel The PWM channel that the Talon SRX is attached to. 0-9 are on-board, 10-19 + * are on the MXP port */ @SuppressWarnings("this-escape") public PWMTalonSRX(final int channel) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVenom.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVenom.java similarity index 80% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVenom.java rename to wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVenom.java index f9960b0278..220f0644c0 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVenom.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVenom.java @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY + package edu.wpi.first.wpilibj.motorcontrol; import edu.wpi.first.hal.FRCNetComm.tResourceType; @@ -9,12 +11,13 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; /** - * Playing with Fusion Venom Smart Motor with PWM control. + * Playing with Fusion Venom Motor Controller. * *

        Note that the Venom uses the following bounds for PWM values. These values should work * reasonably well for most controllers, but if users experience issues such as asymmetric behavior * around the deadband or inability to saturate the controller in either direction, calibration is - * recommended. + * recommended. The calibration procedure can be found in the Venom User Manual available from + * Playing with Fusion. * *

          *
        • 2.004ms = full "forward" @@ -26,10 +29,10 @@ import edu.wpi.first.wpilibj.PWM; */ public class PWMVenom extends PWMMotorController { /** - * Constructor for a Venom connected via PWM. + * Constructor. * - * @param channel The PWM channel that the Venom is attached to. 0-9 are on-board, 10-19 are on - * the MXP port + * @param channel The PWM channel that the Venom is attached to. 0-9 are on-board, 10-19 + * are on the MXP port */ @SuppressWarnings("this-escape") public PWMVenom(final int channel) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVictorSPX.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVictorSPX.java similarity index 86% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVictorSPX.java rename to wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVictorSPX.java index daa70f3478..570d78a3d3 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVictorSPX.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVictorSPX.java @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY + package edu.wpi.first.wpilibj.motorcontrol; import edu.wpi.first.hal.FRCNetComm.tResourceType; @@ -9,13 +11,13 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; /** - * Cross the Road Electronics (CTRE) Victor SPX Motor Controller with PWM control. + * Cross the Road Electronics (CTRE) Victor SPX Motor Controller. * *

          Note that the Victor SPX uses the following bounds for PWM values. These values should work * reasonably well for most controllers, but if users experience issues such as asymmetric behavior * around the deadband or inability to saturate the controller in either direction, calibration is * recommended. The calibration procedure can be found in the Victor SPX User Manual available from - * CTRE. + * Cross the Road Electronics (CTRE). * *

            *
          • 2.004ms = full "forward" @@ -27,9 +29,9 @@ import edu.wpi.first.wpilibj.PWM; */ public class PWMVictorSPX extends PWMMotorController { /** - * Constructor for a Victor SPX connected via PWM. + * Constructor. * - * @param channel The PWM channel that the PWMVictorSPX is attached to. 0-9 are on-board, 10-19 + * @param channel The PWM channel that the Victor SPX is attached to. 0-9 are on-board, 10-19 * are on the MXP port */ @SuppressWarnings("this-escape") diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java similarity index 77% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java rename to wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java index 31246bc5c1..1ee4eebc00 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY + package edu.wpi.first.wpilibj.motorcontrol; import edu.wpi.first.hal.FRCNetComm.tResourceType; @@ -18,19 +20,19 @@ import edu.wpi.first.wpilibj.PWM; * Mindsensors. * *
              - *
            • 2.05ms = full "forward" - *
            • 1.55ms = the "high end" of the deadband range - *
            • 1.50ms = center of the deadband range (off) - *
            • 1.44ms = the "low end" of the deadband range - *
            • 0.94ms = full "reverse" + *
            • 2.050ms = full "forward" + *
            • 1.550ms = the "high end" of the deadband range + *
            • 1.500ms = center of the deadband range (off) + *
            • 1.440ms = the "low end" of the deadband range + *
            • 0.940ms = full "reverse" *
            */ public class SD540 extends PWMMotorController { /** * Constructor. * - * @param channel The PWM channel that the SD540 is attached to. 0-9 are on-board, 10-19 are on - * the MXP port + * @param channel The PWM channel that the SD540 is attached to. 0-9 are on-board, 10-19 + * are on the MXP port */ @SuppressWarnings("this-escape") public SD540(final int channel) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Spark.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Spark.java similarity index 84% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Spark.java rename to wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Spark.java index d57b626a10..e3b86d1efd 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Spark.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Spark.java @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY + package edu.wpi.first.wpilibj.motorcontrol; import edu.wpi.first.hal.FRCNetComm.tResourceType; @@ -14,8 +16,8 @@ import edu.wpi.first.wpilibj.PWM; *

            Note that the SPARK uses the following bounds for PWM values. These values should work * reasonably well for most controllers, but if users experience issues such as asymmetric behavior * around the deadband or inability to saturate the controller in either direction, calibration is - * recommended. The calibration procedure can be found in the Spark User Manual available from REV - * Robotics. + * recommended. The calibration procedure can be found in the SPARK User Manual available from + * REV Robotics. * *

              *
            • 2.003ms = full "forward" @@ -29,8 +31,8 @@ public class Spark extends PWMMotorController { /** * Constructor. * - * @param channel The PWM channel that the SPARK is attached to. 0-9 are on-board, 10-19 are on - * the MXP port + * @param channel The PWM channel that the SPARK is attached to. 0-9 are on-board, 10-19 + * are on the MXP port */ @SuppressWarnings("this-escape") public Spark(final int channel) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Talon.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Talon.java similarity index 82% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Talon.java rename to wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Talon.java index bcbad60738..0e83a17617 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Talon.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Talon.java @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY + package edu.wpi.first.wpilibj.motorcontrol; import edu.wpi.first.hal.FRCNetComm.tResourceType; @@ -9,12 +11,13 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; /** - * Cross the Road Electronics (CTRE) Talon and Talon SR Motor Controller. + * Cross the Road Electronics (CTRE) Talon Motor Controller. * *

              Note that the Talon uses the following bounds for PWM values. These values should work * reasonably well for most controllers, but if users experience issues such as asymmetric behavior * around the deadband or inability to saturate the controller in either direction, calibration is - * recommended. The calibration procedure can be found in the Talon User Manual available from CTRE. + * recommended. The calibration procedure can be found in the Talon User Manual available from + * Cross the Road Electronics (CTRE). * *

                *
              • 2.037ms = full "forward" @@ -26,10 +29,10 @@ import edu.wpi.first.wpilibj.PWM; */ public class Talon extends PWMMotorController { /** - * Constructor for a Talon (original or Talon SR). + * Constructor. * - * @param channel The PWM channel that the Talon is attached to. 0-9 are on-board, 10-19 are on - * the MXP port + * @param channel The PWM channel that the Talon is attached to. 0-9 are on-board, 10-19 + * are on the MXP port */ @SuppressWarnings("this-escape") public Talon(final int channel) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java similarity index 52% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java rename to wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java index 1a816add18..6c6a0c21b0 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY + package edu.wpi.first.wpilibj.motorcontrol; import edu.wpi.first.hal.FRCNetComm.tResourceType; @@ -9,16 +11,13 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; /** - * VEX Robotics Victor 888 Motor Controller The Vex Robotics Victor 884 Motor Controller can also be - * used with this class but may need to be calibrated per the Victor 884 user manual. + * Vex Robotics Victor 888 Motor Controller. * - *

                Note that the Victor uses the following bounds for PWM values. These values were determined - * empirically and optimized for the Victor 888. These values should work reasonably well for Victor - * 884 controllers also but if users experience issues such as asymmetric behavior around the - * deadband or inability to saturate the controller in either direction, calibration is recommended. - * The calibration procedure can be found in the Victor 884 User Manual available from VEX Robotics: - * http://content.vexrobotics.com/docs/ifi-v884-users-manual-9-25-06.pdf + *

                Note that the Victor 888 uses the following bounds for PWM values. These values should work + * reasonably well for most controllers, but if users experience issues such as asymmetric behavior + * around the deadband or inability to saturate the controller in either direction, calibration is + * recommended. The calibration procedure can be found in the Victor 888 User Manual available from + * Vex Robotics. * *

                  *
                • 2.027ms = full "forward" @@ -32,8 +31,8 @@ public class Victor extends PWMMotorController { /** * Constructor. * - * @param channel The PWM channel that the Victor is attached to. 0-9 are on-board, 10-19 are on - * the MXP port + * @param channel The PWM channel that the Victor 888 is attached to. 0-9 are on-board, 10-19 + * are on the MXP port */ @SuppressWarnings("this-escape") public Victor(final int channel) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/VictorSP.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/VictorSP.java similarity index 76% rename from wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/VictorSP.java rename to wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/VictorSP.java index 09ba3c6290..8f0e2f61bc 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/VictorSP.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/VictorSP.java @@ -2,6 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. +// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY + package edu.wpi.first.wpilibj.motorcontrol; import edu.wpi.first.hal.FRCNetComm.tResourceType; @@ -9,13 +11,13 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; /** - * VEX Robotics Victor SP Motor Controller. + * Vex Robotics Victor SP Motor Controller. * - *

                  Note that the VictorSP uses the following bounds for PWM values. These values should work + *

                  Note that the Victor SP uses the following bounds for PWM values. These values should work * reasonably well for most controllers, but if users experience issues such as asymmetric behavior * around the deadband or inability to saturate the controller in either direction, calibration is - * recommended. The calibration procedure can be found in the VictorSP User Manual available from - * CTRE. + * recommended. The calibration procedure can be found in the Victor SP User Manual available from + * Vex Robotics. * *

                    *
                  • 2.004ms = full "forward" @@ -29,8 +31,8 @@ public class VictorSP extends PWMMotorController { /** * Constructor. * - * @param channel The PWM channel that the VictorSP is attached to. 0-9 are on-board, 10-19 are on - * the MXP port + * @param channel The PWM channel that the Victor SP is attached to. 0-9 are on-board, 10-19 + * are on the MXP port */ @SuppressWarnings("this-escape") public VictorSP(final int channel) {