diff --git a/Firmware/.gitignore b/Firmware/.gitignore index 1757ea432..f6faee73a 100644 --- a/Firmware/.gitignore +++ b/Firmware/.gitignore @@ -1,4 +1,4 @@ -/*Debug/ +**/Debug/ **/Release/ **/.settings/ *.launch @@ -7,5 +7,4 @@ .mxproject fixlang /build/ -/OpenFFBoard/ -/*Targets/F407VG/*.cfg +/OpenFFBoard/ \ No newline at end of file diff --git a/Firmware/FFBoard/Inc/AxesManager.h b/Firmware/FFBoard/Inc/AxesManager.h index f1b9e3762..fb361e127 100644 --- a/Firmware/FFBoard/Inc/AxesManager.h +++ b/Firmware/FFBoard/Inc/AxesManager.h @@ -47,10 +47,10 @@ class AxesManager void emergencyStop(bool reset); void resetPosZero(); + void updateSamplerate(float newSamplerate); + private: volatile Control_t* control; - volatile bool *p_usb_disabled; - volatile bool *p_emergency; std::shared_ptr effects_calc; uint16_t axis_count = 0; std::vector> axes; diff --git a/Firmware/FFBoard/Inc/Axis.h b/Firmware/FFBoard/Inc/Axis.h index 05e87fdc9..6603eb5cb 100644 --- a/Firmware/FFBoard/Inc/Axis.h +++ b/Firmware/FFBoard/Inc/Axis.h @@ -2,7 +2,9 @@ * Axis.h * * Created on: 21.01.2021 - * Author: Yannick / Lidders + * Author: Yannick / Lidders / Vincent + * + * Release 27.10.25: Vincent, add reconstruction filter, equalizer, slew rate. */ #ifndef SRC_AXIS_H_ @@ -10,7 +12,6 @@ #include #include #include "usb_hid_ffb_desc.h" -#include "TMC4671.h" #include "PersistentStorage.h" #include "ButtonSource.h" #include "EncoderLocal.h" @@ -24,6 +25,10 @@ #include "ExtiHandler.h" #include "EffectsCalculator.h" +#ifdef USE_DSP_FUNCTIONS +#include "arm_math.h" +#endif + #define INTERNAL_AXIS_DAMPER_SCALER 0.7 #define INTERNAL_AXIS_FRICTION_SCALER 0.7 #define INTERNAL_AXIS_INERTIA_SCALER 0.7 @@ -34,22 +39,28 @@ #define AXIS_SPEEDLIMITER_I 0.03 #endif - +/** + * @brief Global control flags for all axes. + */ struct Control_t { - bool emergency = false; - bool usb_disabled = true; - bool update_disabled = true; - bool request_update_disabled = false; + bool emergency = false; //!< Emergency stop is active. + bool usb_disabled = true; //!< FFB is disabled by USB. + bool update_disabled = true; //!< FFB updates are disabled. + bool request_update_disabled = false; //!< A request to disable FFB updates is pending. // bool usb_update_flag = false; // bool update_flag = false; - bool resetEncoder = false; + bool resetEncoder = false; //!< A request to reset the encoder is pending. }; -struct AxisFlashAddrs +/** + * @brief Defines the flash memory addresses for axis-specific settings. + */ +struct AxisFlashAddresses { uint16_t config = ADR_AXIS1_CONFIG; uint16_t maxSpeed = ADR_AXIS1_MAX_SPEED; uint16_t maxAccel = ADR_AXIS1_MAX_ACCEL; + uint16_t maxSlewRateDrv = ADR_AXIS1_MAX_SLEWRATE_DRV; uint16_t endstop = ADR_AXIS1_ENDSTOP; uint16_t power = ADR_AXIS1_POWER; @@ -62,229 +73,462 @@ struct AxisFlashAddrs uint16_t postprocess1 = ADR_AXIS1_POSTPROCESS1; }; +/** + * @brief Configuration for an axis, including driver and encoder types. + */ struct AxisConfig { - uint8_t drvtype = 0; - uint8_t enctype = 0; - //bool invert = false; + uint8_t drvtype = 0; //!< Motor driver type ID. + uint8_t enctype = 0; //!< Encoder type ID. }; +/** + * @brief Holds the physical metrics of an axis at a point in time. + */ struct metric_t { - float accel = 0; // in deg/s² - float speed = 0; // in deg/s - int32_t pos = 0; // scaled position as 16b int -0x7fff to 0x7fff - float pos_f = 0; // scaled position as float. -1 to 1 range - float posDegrees = 0; // Position in degrees. Not scaled to selected range - int32_t torque = 0; // total of effect + endstop torque + float accel = 0; //!< Acceleration in deg/s². + float speed = 0; //!< Speed in deg/s. + int32_t pos_scaled_16b = 0; //!< Scaled position as a 16-bit integer (-0x7fff to 0x7fff). + float pos_f = 0; //!< Scaled position as a float (-1.0 to 1.0). + float posDegrees = 0; //!< Position in degrees, not scaled to the selected range. + int32_t torque = 0; //!< Total torque applied to the axis. }; +/** + * @brief Holds the current and previous metrics for an axis, used for calculating derivatives. + */ struct axis_metric_t { - metric_t current; - metric_t previous; + metric_t current; //!< Current metrics. + metric_t previous; //!< Metrics from the previous update cycle. }; +/** + * @brief Represents a gear ratio for scaling encoder values. + */ struct GearRatio_t{ - uint8_t denominator = 0; - uint8_t numerator = 0; - float gearRatio = 1.0; + uint8_t denominator = 0; //!< Denominator of the gear ratio. + uint8_t numerator = 0; //!< Numerator of the gear ratio. + float gearRatio = 1.0; //!< The calculated gear ratio (numerator/denominator). }; - enum class Axis_commands : uint32_t{ power=0x00,degrees=0x01,esgain,zeroenc,invert,idlespring,axisdamper,enctype,drvtype, - pos,maxspeed,maxtorquerate,fxratio,curtorque,curpos,curspd,curaccel,reductionScaler, + pos,curtorque,curpos,curspd,curaccel, + fxratio,reductionScaler, filterSpeed, filterAccel, filterProfileId,cpr,axisfriction,axisinertia, + maxspeed,slewrate, + calibrate_maxSlewRateDrv, + maxSlewRateDrv, expo,exposcale }; +/** + * @brief This class represents a single FFB axis. + * It handles the motor driver, encoder, and all related calculations for force feedback effects. + */ class Axis : public PersistentStorage, public CommandHandler, public ErrorHandler { public: + /** + * @brief Construct a new Axis object. + * @param axis The character identifier for this axis (e.g., 'x', 'y'). + * @param control A pointer to the global control structure. + */ Axis(char axis, volatile Control_t* control); virtual ~Axis(); - static ClassIdentifier info; + static ClassIdentifier info; //!< Static class identifier. const ClassIdentifier getInfo(); const ClassType getClassType() override {return ClassType::Axis;}; virtual std::string getHelpstring() { return "FFB axis" ;} -#ifdef TMC4671DRIVER - void setupTMC4671(); -#endif // Dynamic classes + /** + * @brief Sets the motor driver type. + * @param drvtype The type of the motor driver. + */ void setDrvType(uint8_t drvtype); + + /** + * @brief Sets the encoder type. + * @param enctype The type of the encoder. + */ void setEncType(uint8_t enctype); + + /** + * @brief Gets the motor driver type. + * @return The type of the motor driver. + */ uint8_t getDrvType(); + + /** + * @brief Gets the encoder type. + * @return The type of the encoder. + */ uint8_t getEncType(); + /** + * @brief Gets the encoder instance. + * @return A pointer to the encoder instance. + */ Encoder* getEncoder(); + + /** + * @brief Gets the motor driver instance. + * @return A pointer to the motor driver instance. + */ MotorDriver* getDriver(); - void usbSuspend(); // Called on usb disconnect and suspend - void usbResume(); // Called on usb resume + /** + * @brief Called on USB disconnect and suspend. + */ + void usbSuspend(); + + /** + * @brief Called on USB resume. Enables the motor driver. + */ + void usbResume(); + /** + * @brief Saves axis settings to flash memory. + * @override from PersistentStorage + */ void saveFlash() override; + + /** + * @brief Restores axis settings from flash memory. + * @override from PersistentStorage + */ void restoreFlash() override; - void prepareForUpdate(); // called before the effects are calculated - void updateDriveTorque(); //int32_t effectTorque); + /** + * @brief Prepares the axis for an update cycle. Called from the main loop before effects are calculated. + * Reads the encoder, scales the value, and updates metrics (speed, acceleration). + */ + void prepareForUpdate(); + + /** + * @brief Sends the final calculated torque to the motor driver. + */ + void updateDriveTorque(); + + /** + * @brief Triggers an emergency stop. Disables the motor driver. + * @param reset If true, resets the axis after stopping. + */ void emergencyStop(bool reset); + /** + * @brief Sets the position of the axis. + * @param val The new position value. + */ void setPos(uint16_t val); + + /** + * @brief Zeros the current encoder position. + */ void zeroPos(); + /** + * @brief Checks if FFB is globally active. + * @return true if FFB is active, false otherwise. + */ bool getFfbActive(); + /** + * @brief Scales an encoder value. + * @param angle The angle to scale. + * @param degrees The total degrees of rotation. + * @return A pair containing the scaled integer value and the float value. + */ std::pair scaleEncValue(float angle, uint16_t degrees); - float getEncAngle(Encoder *enc); + /** + * @brief Gets the angle from the encoder. + * @param enc A pointer to the encoder. + * @return The angle in degrees. + */ + float getEncAngle(Encoder *enc); + /** + * @brief Sets the maximum power (torque) of the motor. + * @param power The new power value. + */ void setPower(uint16_t power); - + /** + * @brief Callback for handling errors. + * @param error The error that occurred. + * @param cleared Whether the error has been cleared. + * @override from ErrorHandler + */ void errorCallback(const Error &error, bool cleared) override; - //ParseStatus command(ParsedCommand_old* cmd,std::string* reply) override; + /** + * @brief Registers the commands for this axis with the command handler. + */ void registerCommands(); - CommandStatus command(const ParsedCommand& cmd,std::vector& replies); - - ClassChooser drv_chooser; - ClassChooser enc_chooser; - + /** + * @brief Handles command line interface commands for this axis. + * @param cmd The parsed command. + * @param replies A vector of replies to be sent back. + * @return The status of the command execution. + * @override from CommandHandler + */ + CommandStatus command(const ParsedCommand& cmd,std::vector& replies) override; + + ClassChooser driverChooser; //!< Class chooser for motor drivers. + ClassChooser encoderChooser; //!< Class chooser for encoders. + + /** + * @brief Gets the last scaled encoder value. + * @return The last scaled encoder value. + */ int32_t getLastScaledEnc(); + + /** + * @brief Resets the metrics of the axis. + * @param new_pos The new position to reset to. + */ void resetMetrics(float new_pos); + + /** + * @brief Updates the metrics of the axis. + * @param new_pos The new position. + */ void updateMetrics(float new_pos); + + /** + * @brief Updates the idle spring force. + * @return The calculated idle spring force. + */ int32_t updateIdleSpringForce(); + + /** + * @brief Sets the idle spring strength. + * @param spring The new spring strength. + */ void setIdleSpringStrength(uint8_t spring); - void setFxStrengthAndFilter(uint8_t val,uint8_t& valToSet, Biquad& filter); - void calculateAxisEffects(bool ffb_on); - int32_t getTorque(); // current torque scaled as a 32 bit signed value - int16_t updateEndstop(); - int32_t calculateExpoTorque(int32_t torque); + /** + * @brief Sets the strength and filter for an effect. + * @param val The new strength value. + * @param valToSet A reference to the value to be set. + * @param filter A reference to the biquad filter. + */ + void setFxStrengthAndFilter(uint8_t val,uint8_t& valToSet, Biquad& filter); + /** + * @brief Calculates the mechanical effects (damper, friction, inertia) that are always active. + * These are separate from the HID FFB effects sent by the game. + * @param ffb_on A flag indicating if FFB is on. + */ + void calculateMechanicalEffects(bool ffb_on); + + /** + * @brief Gets the current torque. + * @return The current torque scaled as a 32-bit signed value. + */ + int32_t getTorque(); + + /** + * @brief Calculates the endstop torque. + * @return The calculated endstop torque. + */ + int32_t calculateEndstopTorque(); + + /** + * @brief Calculates the FFB torque exponential torque, from the input torque and apply expo and scaler + * @return The calculated exponential torque. + */ + int64_t calculateFFBTorque(); + + /** + * @brief Starts a force fade-in. + * @param start The starting force multiplier. + * @param fadeTime The duration of the fade-in. + */ void startForceFadeIn(float start = 0,float fadeTime = 0.5); metric_t* getMetrics(); - void setEffectTorque(int32_t torque); + /** + * @brief Sets the FFB effect torque. + * @param torque The new FFB effect torque from the EffectsCalculator. + */ + void setFfbEffectTorque(int64_t torque); + + /** + * @brief Updates the total torque. + * @param totalTorque A pointer to the total torque value. + * @return true if the torque was updated, false otherwise. + */ bool updateTorque(int32_t* totalTorque); + void updateSamplerate(float newSamplerate); + void updateFilters(uint8_t profileId); + + /** + * @brief Sets the gear ratio. + * @param numerator The numerator of the gear ratio. + * @param denominator The denominator of the gear ratio. + */ void setGearRatio(uint8_t numerator,uint8_t denominator); - static const std::vector> axis1_drivers; - static const std::vector> axis2_drivers; + static const std::vector> axis1_drivers; //!< List of available motor drivers for the first axis. + static const std::vector> axis2_drivers; //!< List of available motor drivers for the second axis. private: - // Axis damper is lower than default scale of HID Damper + // Internal constants const float AXIS_DAMPER_RATIO = INTERNAL_SCALER_DAMPER * INTERNAL_AXIS_DAMPER_SCALER / 255.0; const float AXIS_INERTIA_RATIO = INTERNAL_SCALER_INERTIA * INTERNAL_AXIS_INERTIA_SCALER / 255.0; - AxisFlashAddrs flashAddrs; - volatile Control_t* control; + // Private methods + /** + * @brief Sets the degrees of rotation for the axis. + * @param degrees The new range of rotation. + */ + void setDegrees(uint16_t degrees); + /** + * @brief Returns the current power setting of the axis. + * @return The power value. + */ + uint16_t getPower(); + /** + * @brief Returns the calculated torque scaler. + * @return The torque scaler value. + */ + bool isInverted(); + /** + * @brief Sets the ratio between game effects and endstop force and updates the internal torque scaler based on power and fx_ratio + * @param val The new ratio value (0-255). + */ + void setEffectRatio(uint8_t val); + /** + * @brief Sets the exponential torque curve. + * @param val The new expo value. + */ + void setExpo(int val); - //TIM_HandleTypeDef *timer_update; - AxisConfig conf; + int32_t calculateExpoTorque(int32_t torque); + /** + * @brief Applies the speed limiter PI controller to the torque. + * @param torque A reference to the torque value to be modified. + * @return torque update to apply to reduced de speed. + */ + int64_t applySpeedLimiterTorque(int64_t& torque); + /** + * @brief Applies the torque slew rate limiter to the torque. + * @param torque A reference to the torque value to be modified. + */ + void applyTorqueSlewRateLimiter(int64_t& torque); + /** + * @brief Decodes the axis configuration from a 16-bit integer stored in flash. + * @param val The 16-bit encoded configuration value. + */ + static AxisConfig decodeConfFromInt(uint16_t val); + /** + * @brief Encodes the axis configuration into a 16-bit integer for flash storage. + * @param conf The AxisConfig struct to encode. + * @return The encoded 16-bit value. + */ + static uint16_t encodeConfToInt(AxisConfig conf); - std::unique_ptr drv = std::make_unique(); // dummy - std::shared_ptr enc = nullptr; - bool outOfBounds = false; - static AxisConfig decodeConfFromInt(uint16_t val); - static uint16_t encodeConfToInt(AxisConfig conf); + // Member variables + AxisFlashAddresses flashAddresses; //!< Flash memory addresses for this axis. + volatile Control_t* control; //!< Pointer to the global control structure. + AxisConfig conf; //!< Configuration for this axis (driver and encoder types). + char axis; //!< Axis identifier ('X', 'Y', 'Z'). - const Error outOfBoundsError = Error(ErrorCode::axisOutOfRange,ErrorType::warning,"Axis out of bounds"); + std::unique_ptr drv = std::make_unique(); //!< Unique pointer to the active motor driver. + std::shared_ptr enc = nullptr; //!< Shared pointer to the active encoder. - float forceFadeTime = 1.0; - float forceFadeCurMult = 1.0; + bool outOfBounds = false; //!< Flag indicating if the axis is out of its valid range. + const Error outOfBoundsError = Error(ErrorCode::axisOutOfRange,ErrorType::warning,"Axis out of bounds"); //!< Error object for out-of-bounds condition. -#ifdef TMC4671DRIVER - TMC4671Limits tmclimits = TMC4671Limits({.pid_torque_flux_ddt = 32767, - .pid_uq_ud = 30000, - .pid_torque_flux = 30000, - .pid_acc_lim = 2147483647, - .pid_vel_lim = 2147483647, - .pid_pos_low = -2147483647, - .pid_pos_high = 2147483647}); -#endif - float encoderOffset = 0; // Offset for absolute encoders - uint16_t degreesOfRotation = 900; // How many degrees of range for the full gamepad range - uint16_t lastdegreesOfRotation = degreesOfRotation; // Used to store the previous value - uint16_t nextDegreesOfRotation = degreesOfRotation; // Buffer when changing range + // Force fade-in effect + float forceFadeDuration = 1.0; //!< Duration of the force fade-in in seconds. + float forceFadeMultiplier = 1.0; //!< Current multiplier for the force fade-in. - // Limiters - uint16_t maxSpeedDegS = 0; // Set to non zero to enable. example 1000. 8b * 10? - //float maxAccelDegSS = 0; - uint32_t maxTorqueRateMS = 0; // 8b * 128? - float speedLimiterP = AXIS_SPEEDLIMITER_P; - float speedLimiterI = AXIS_SPEEDLIMITER_I; + float encoderOffset = 0; //!< Offset for absolute encoders. + uint16_t degreesOfRotation = 900; //!< Current degrees of rotation. + uint16_t previousDegreesOfRotation = degreesOfRotation; //!< Previous degrees of rotation (for smooth transitions). + uint16_t nextDegreesOfRotation = degreesOfRotation; //!< Target degrees of rotation. - float spdlimitreducerI = 0; - //float acclimitreducerI = 0; - //const uint8_t accelFactor = 10.0; // Conversion factor between internal and external acc limit + // Limiters + uint16_t maxSlewRate_Driver = MAX_SLEW_RATE; //!< Maximum slew rate as measured by the driver (in units/ms). + uint16_t maxSpeedDegS = 0; //!< Maximum speed in degrees per second. 0 to disable. + uint32_t maxTorqueRateMS = 0; //!< Maximum torque rate of change per millisecond. 0 to disable. + + float speedLimiterP = AXIS_SPEEDLIMITER_P; //!< Proportional term for the speed limiter. + float speedLimiterI = AXIS_SPEEDLIMITER_I; //!< Integral term for the speed limiter. +#ifdef USE_DSP_FUNCTIONS + arm_pid_instance_f32 speedLimiterPID; //!< PID instance for the speed limiter. +#else + // Speed limiter PID + float speedLimitReducerI = 0; +#endif - void setDegrees(uint16_t degrees); + // Axis metrics + axis_metric_t metric; //!< Current and previous physical metrics of the axis. + float previousFrameSpeed = 0; //!< Instantaneous speed from the last cycle, used for acceleration calculation. - uint16_t getPower(); - float getTorqueScaler(); - bool isInverted(); - char axis; + // Torque components + int64_t ffbEffectTorque = 0; //!< Torque from HID FFB effects. + int32_t mechanicalEffectTorque = 0; //!< Torque from mechanical effects (damper, friction, inertia). + // Power and scaling + uint16_t power = 5000; //!< Maximum motor power/torque. + uint8_t effectRatio = 204; //!< Ratio of HID effects vs. endstop effects (0-255). + float effectRatioScaler = 0; //!< Scaler for HID effects based on effectRatio. + float torqueScaler = 0; //!< Final torque scaler based on power. - // Merge normalized - axis_metric_t metric; - float _lastSpeed = 0; - int32_t effectTorque = 0; - int32_t axisEffectTorque = 0; - uint8_t fx_ratio_i = 204; // Reduce effects to a certain ratio of the total power to have a margin for the endstop. 80% = 204 - uint16_t power = 5000; - float torqueScaler = 0; // power * fx_ratio as a ratio between 0 & 1 - float effect_margin_scaler = 0; - bool invertAxis = true; // By default most motors and encoders count up CCW while gamepads are counting up CW. - uint8_t endstopStrength = 127; // Sets how much extra torque per count above endstop is added. High = stiff endstop. Low = softer - const float endstopGain = 25; // Overall max endstop intensity + // Axis configuration + bool invertAxis = true; //!< Invert axis direction. + uint8_t endstopStrength = 127; //!< Stiffness of the endstop effect. + const float endstopGain = 25; //!< Overall maximum endstop intensity. + // Idle spring effect + uint8_t idleSpringStrength = 127; //!< Strength of the idle spring. + int16_t idleSpringClip = 0; //!< Maximum force for the idle spring. + float idleSpringScale = 0; //!< Scaler for the idle spring force. + bool motorWasNotReady = true; //!< Flag to detect motor readiness transition. - uint8_t idlespringstrength = 127; - int16_t idlespringclip = 0; - float idlespringscale = 0; - bool motorWasNotReady = true; + // Slew rate calibration tracking: true when Axis requested a calibration and + // is waiting for the driver to finish measuring the max slew rate. + bool awaitingSlewCalibration = false; + // Filters // TODO tune these and check if it is really stable and beneficial to the FFB. index 4 placeholder - const std::array filterSpeedCst = { {{ 40, 55 }, { 70, 55 }, { 120, 55 }, {180, 55}} }; - const std::array filterAccelCst = { {{ 40, 30 }, { 55, 30 }, { 70, 30 }, {120, 55}} }; - const biquad_constant_t filterDamperCst = {60, 55}; - const biquad_constant_t filterFrictionCst = {50, 20}; - const biquad_constant_t filterInertiaCst = {20, 20}; - uint8_t filterProfileId = 1; // Default medium (1) as this is the most common encoder resolution and users can go lower or higher if required. - const float filter_f = 1000; // 1khz - const int32_t intFxClip = 20000; - uint8_t damperIntensity = 30; - - uint8_t frictionIntensity = 0; - uint8_t inertiaIntensity = 0; - + const std::array filterSpeedCst = { {{ 40, 55 }, { 70, 55 }, { 120, 55 }, {180, 55}} }; //!< Speed filter profiles. + const std::array filterAccelCst = { {{ 40, 30 }, { 55, 30 }, { 70, 30 }, {120, 55}} }; //!< Acceleration filter profiles. + const biquad_constant_t filterDamperCst = {60, 55}; //!< Damper filter constants. + const biquad_constant_t filterFrictionCst = {50, 20}; //!< Friction filter constants. + const biquad_constant_t filterInertiaCst = {20, 20}; //!< Inertia filter constants. + uint8_t filterProfileId = 1; //!< Currently selected filter profile ID. + float filter_f = 1000.0; // 1khz + const int32_t internalFxClip = 20000; //!< Clipping value for internal effects. + + // Internal effects intensity + uint8_t damperIntensity = 30; //!< Intensity of the internal damper effect. + uint8_t frictionIntensity = 0; //!< Intensity of the internal friction effect. + uint8_t inertiaIntensity = 0; //!< Intensity of the internal inertia effect. + + // Biquad filter instances Biquad speedFilter = Biquad(BiquadType::lowpass, filterSpeedCst[filterProfileId].freq/filter_f, filterSpeedCst[filterProfileId].q/100.0, 0.0); Biquad accelFilter = Biquad(BiquadType::lowpass, filterAccelCst[filterProfileId].freq/filter_f, filterAccelCst[filterProfileId].q/100.0, 0.0); - Biquad damperFilter = Biquad(BiquadType::lowpass, filterDamperCst.freq/filter_f, filterDamperCst.q / 100.0, 0.0); // enable on class constructor - Biquad frictionFilter = Biquad(BiquadType::lowpass, filterFrictionCst.freq/filter_f, filterFrictionCst.q / 100.0, 0.0); // enable on class constructor - Biquad inertiaFilter = Biquad(BiquadType::lowpass, filterInertiaCst.freq/filter_f, filterInertiaCst.q / 100.0, 0.0); // enable on class constructor - - - void setFxRatio(uint8_t val); - void updateTorqueScaler(); - - void setExpo(int val); - - - GearRatio_t gearRatio; - - int expoValInt = 0; // expo v = val*2 => v<0 ? 1/-v : v - float expo = 1; - float expoScaler = 50; // 0.28 to 3.54 - + Biquad damperFilter = Biquad(BiquadType::lowpass, filterDamperCst.freq/filter_f, filterDamperCst.q / 100.0, 0.0); + Biquad frictionFilter = Biquad(BiquadType::lowpass, filterFrictionCst.freq/filter_f, filterFrictionCst.q / 100.0, 0.0); + Biquad inertiaFilter = Biquad(BiquadType::lowpass, filterInertiaCst.freq/filter_f, filterInertiaCst.q / 100.0, 0.0); + + // Post-processing + GearRatio_t gearRatio; //!< Gear ratio between encoder and axis. + int expoValue = 0; //!< Raw integer value for the expo curve. Formula: v = val*2 => v<0 ? 1/-v : v + float expo = 1; //!< Calculated exponent for the torque curve. + float expoScaler = 50; //!< Scaler for the expo calculation : 0.28 to 3.54 }; #endif /* SRC_AXIS_H_ */ diff --git a/Firmware/FFBoard/Inc/CAN.h b/Firmware/FFBoard/Inc/CAN.h index d58a31841..06357e6ed 100644 --- a/Firmware/FFBoard/Inc/CAN.h +++ b/Firmware/FFBoard/Inc/CAN.h @@ -11,6 +11,7 @@ #ifdef CANBUS //#include "CanHandler.h" #include "main.h" +#include #include #include "semaphore.hpp" #include diff --git a/Firmware/FFBoard/Inc/CmdParser.h b/Firmware/FFBoard/Inc/CmdParser.h index 48094d3c5..be3221884 100644 --- a/Firmware/FFBoard/Inc/CmdParser.h +++ b/Firmware/FFBoard/Inc/CmdParser.h @@ -17,7 +17,9 @@ #include "CommandHandler.h" #include "ringbufferwrapper.h" +#ifndef CMDPARSER_MAX_VALID_CAPACITY #define CMDPARSER_MAX_VALID_CAPACITY 2048 +#endif class CommandHandler; class CommandInterface; diff --git a/Firmware/FFBoard/Inc/CommandHandler.h b/Firmware/FFBoard/Inc/CommandHandler.h index 0a5cb92a7..71c005a53 100644 --- a/Firmware/FFBoard/Inc/CommandHandler.h +++ b/Firmware/FFBoard/Inc/CommandHandler.h @@ -13,7 +13,7 @@ #include "mutex.hpp" #include "ClassIDs.h" #include - +#include #define CMDFLAG_GET 0x01 #define CMDFLAG_SET 0x02 @@ -22,6 +22,7 @@ #define CMDFLAG_SETADR 0x20 #define CMDFLAG_HIDDEN 0x40 #define CMDFLAG_DEBUG 0x80 +#define CMDFLAG_EXTOVERRIDE 0x80000000 #define CMDFLAG_STR_ONLY 0x100 #define CMDFLAG_HID_ONLY 0x200 // Command not available for string based parsers @@ -50,8 +51,8 @@ class CmdHandlerCommanddef {}; const char* cmd = nullptr; const char* helpstring = nullptr; - const uint32_t cmdId; - const uint32_t flags; + uint32_t cmdId; + uint32_t flags; }; struct CmdHandlerInfo @@ -260,17 +261,22 @@ class CommandHandler { */ template void registerCommand(const char* cmd,const ID cmdid,const char* help=nullptr,uint32_t flags = 0){ - for(CmdHandlerCommanddef& cmdDef : registeredCommands){ - if(cmdDef.cmdId == static_cast(cmdid)) - return; //already present - } + registerCommand_INT(cmd, static_cast(cmdid), help, flags); + } - this->registeredCommands.emplace_back(cmd, help,static_cast(cmdid),flags); - this->registeredCommands.shrink_to_fit(); + + virtual void postCmdhandlerInit(){}; // Can implement in external file to override command flags + template + /** + * Can override command flags to make it read only + */ + void overrideCommandFlags(const ID cmdid,uint32_t flagmask = 0){ + overrideCommandFlags_INT(static_cast(cmdid), flagmask); } + protected: void setInstance(uint8_t instance); bool commandsEnabled = true; @@ -287,6 +293,9 @@ class CommandHandler { CmdHandlerInfo cmdHandlerInfo; + void registerCommand_INT(const char* cmd,const uint32_t cmdid,const char* help=nullptr,uint32_t flags = 0); + void overrideCommandFlags_INT(const uint32_t cmdid,uint32_t flagmask = CMDFLAG_GET | CMDFLAG_GETADR); + }; #endif /* COMMANDHANDLER_H_ */ diff --git a/Firmware/FFBoard/Inc/CommandInterface.h b/Firmware/FFBoard/Inc/CommandInterface.h index d99ec7b92..b70a57da6 100644 --- a/Firmware/FFBoard/Inc/CommandInterface.h +++ b/Firmware/FFBoard/Inc/CommandInterface.h @@ -60,7 +60,7 @@ class StringCommandInterface : public CommandInterface{ CmdParser parser; // String parser }; - +#define CDC_CMD_BUFFER_SIZE (TUD_OPT_HIGH_SPEED ? 4096 : 1024) //receives bytes from mainclass. calls its own parser instance, calls global parser thread, passes replies back to cdc port. class CDC_CommandInterface : public StringCommandInterface,public cpp_freertos::Thread{ public: @@ -83,7 +83,7 @@ class CDC_CommandInterface : public StringCommandInterface,public cpp_freertos:: bool nextFormat = false; std::string sendBuffer; uint32_t bufferLength = 0; - const uint32_t maxSendBuffer = 1024; // Max buffered command size before sending immediately + const uint32_t maxSendBuffer = CDC_CMD_BUFFER_SIZE; // Max buffered command size before sending immediately }; diff --git a/Firmware/FFBoard/Inc/EffectsCalculator.h b/Firmware/FFBoard/Inc/EffectsCalculator.h index e065c0335..adec8d5ad 100644 --- a/Firmware/FFBoard/Inc/EffectsCalculator.h +++ b/Firmware/FFBoard/Inc/EffectsCalculator.h @@ -27,7 +27,16 @@ class Axis; struct metric_t; -// default effect gains +enum class ReconFilterMode : uint8_t { + NO_RECONSTRUCTION = 0, + LINEAR_INTERPOLATION = 1, // More responsive, attempts to match the game's signal precisely. Can feel "grainy" if slew rate is high. + SPLINE_CUBIC_NATURAL = 2, // Highest fidelity, smooth curve through last 4 points. More CPU intensive. + SPLINE_CUBIC_HERMITE = 3 // Mixed solution, good fidelity and optimized timing +}; + +/** + * @brief Default gains for conditional effects. + */ struct effect_gain_t { uint8_t friction = 254; uint8_t spring = 64; @@ -35,6 +44,9 @@ struct effect_gain_t { uint8_t inertia = 127; }; +/** + * @brief Scaler values for conditional effects to adjust their intensity. + */ struct effect_scaler_t { float friction = 1.0; //0.4 * 40; float spring = 16.0; @@ -42,6 +54,9 @@ struct effect_scaler_t { float inertia = 2.0;//0.5 * 40; }; +/** + * @brief Biquad filter coefficients for various effects. + */ struct effect_biquad_t { biquad_constant_t constant = { 500, 70 }; biquad_constant_t friction = { 50, 20 }; @@ -49,10 +64,13 @@ struct effect_biquad_t { biquad_constant_t inertia = { 15, 20 }; }; +/** + * @brief Statistics for each effect type. + */ struct effect_stat_t { - std::array current={0}; - std::array max={0}; - uint16_t nb=0; + std::array current={0}; //!< Current force value. + std::array max={0}; //!< Maximum force value since reset. + uint16_t nb=0; //!< Number of times this effect has been used. }; enum class EffectsCalculator_commands : uint32_t { @@ -60,8 +78,13 @@ enum class EffectsCalculator_commands : uint32_t { damper_f, damper_q, friction_f, friction_q, inertia_f, inertia_q, filterProfileId, frictionPctSpeedToRampup, monitorEffect, effectsDetails, effectsForces, + reconFilterMode }; +/** + * @brief This class is responsible for calculating the forces of all active FFB effects. + * It runs in its own thread to perform the calculations. + */ class EffectsCalculator: public PersistentStorage, public CommandHandler, cpp_freertos::Thread { @@ -69,94 +92,288 @@ class EffectsCalculator: public PersistentStorage, EffectsCalculator(); virtual ~EffectsCalculator(); - static ClassIdentifier info; + static ClassIdentifier info; //!< Static class identifier. + /** + * @brief Returns the class identifier. + * @return The class identifier. + */ const ClassIdentifier getInfo(); const ClassType getClassType() override {return ClassType::Internal;}; - void saveFlash(); - void restoreFlash(); + /** + * @brief Saves effect settings to flash memory. + * @override from PersistentStorage + */ + void saveFlash() override; + /** + * @brief Restores effect settings from flash memory. + * @override from PersistentStorage + */ + void restoreFlash() override; + + /** + * @brief Checks if the effects calculator is active. + * @return true if active, false otherwise. + */ bool isActive(); + + /** + * @brief Sets the active state of the effects calculator. + * @param active The new active state. + */ void setActive(bool active); + + /** + * @brief This is the main calculation method. It iterates through all active effects and sums up the forces for each axis. + * @param axes A reference to the vector of axes. + */ void calculateEffects(std::vector> &axes); + + /** + * @brief Sets the filters for a specific effect. + * @param effect A pointer to the effect. + */ virtual void setFilters(FFB_Effect* effect); + + /** + * @brief Sets the global gain for all effects. + * @param gain The new gain value. + */ void setGain(uint8_t gain); + + /** + * @brief Gets the global gain. + * @return The current global gain value. + */ uint8_t getGain(); + + /** + * @brief Logs the usage of an effect type for statistics. + * @param type The effect type. + * @param remove True to decrement the usage count, false to increment. + */ void logEffectType(uint8_t type,bool remove = false); - //void setDirectionEnableMask(uint8_t mask); - void calcStatsEffectType(uint8_t type, int16_t force,uint8_t axis); + + /** + * @brief Calculates and stores statistics for a given effect type. + * @param type The effect type. + * @param force The calculated force. + * @param axis The axis index. + */ + void calcStatsEffectType(uint8_t type, int32_t force,uint8_t axis); + + /** + * @brief Logs the state of an effect (start/stop). + * @param type The effect type. + * @param state The new state. + */ void logEffectState(uint8_t type,uint8_t state); + + /** + * @brief Resets the statistics of active effects. + * @param reinit If true, re-initializes the stats based on currently active effects. + */ void resetLoggedActiveEffects(bool reinit); + /** + * @brief Finds a free slot for a new effect. + * @param type The type of the effect. + * @return The index of the free slot, or -1 if no slot is available. + */ int32_t find_free_effect(uint8_t type); + + /** + * @brief Frees an effect slot. + * @param idx The index of the effect to free. + */ void free_effect(uint16_t idx); - CommandStatus command(const ParsedCommand& cmd,std::vector& replies); + /** + * @brief Met à jour les tampons d'interpolation pour un effet non-conditionnel. + * Appelé par le handler HID (ex: 60Hz). + * @param effect Pointeur vers l'effet à modifier. + * @param new_magnitude Nouvelle magnitude/amplitude cible. + * @param new_offset Nouvel offset cible (utilisé uniquement si is_periodic est true). + * @param is_periodic Si true, met à jour les deux tampons (mag + offset). + */ + void pushReconFilterValue(FFB_Effect* effect, float new_magnitude, float new_offset, bool is_periodic); + + /** + * @brief Handles command line interface commands for the effects calculator. + * @param cmd The parsed command. + * @param replies A vector of replies to be sent back. + * @return The status of the command execution. + * @override from CommandHandler + */ + CommandStatus command(const ParsedCommand& cmd,std::vector& replies) override; virtual std::string getHelpstring() { return "Controls internal FFB effects"; } static const uint32_t max_effects = MAX_EFFECTS; - std::array effects; // Main effects storage + std::array effects; //!< Main effects storage array. + + /** + * @brief The main loop for the effects calculator thread. + * @override from cpp_freertos::Thread + */ + void Run() override; - // Thread impl - void Run(); + void updateSamplerate(float newSamplerate); // Must be called if update rate is changed to update filters and effects protected: private: - //uint8_t directionEnableMask = 0; // Filters - effect_biquad_t filter[2]; // 0 is the default profile and the custom for CFFilter, CUSTOM_PROFILE_ID is the custom slot - uint8_t filterProfileId = 0; - const uint32_t calcfrequency = 1000; // HID frequency 1khz - const float qfloatScaler = 0.01; + effect_biquad_t filter[2]; //!< Filter coefficients for CFFilter, default (0) and custom (1) profiles. + uint8_t filterProfileId = 0; //!< Currently active filter profile (0 or 1). + uint32_t calcfrequency = 1000; //!< Calculation frequency in Hz (matches HID rate 1khz). + const float qfloatScaler = 0.01; //!< Scaler for Q factor. - // Rescale factor for conditional effect to boost or decrease the intensity - uint8_t global_gain = 0xff; - effect_gain_t gain; - effect_scaler_t scaler; - uint8_t frictionPctSpeedToRampup = 25; // define the max value of the range (0..5% of maxspeed) where torque is rampup on friction + // Gains and scalers + uint8_t global_gain = 0xff; //!< Global gain for all effects. + effect_gain_t gain; //!< Per-effect type gains. + effect_scaler_t scaler; //!< Per-effect type intensity scalers. + uint8_t frictionPctSpeedToRampup = 25; //!< Speed percentage for friction ramp-up. : define the max value of the range (0..5% of maxspeed) where torque is rampup on friction // FFB status - bool effects_active = false; // If FFB is on - uint32_t effects_used = 0; - std::array effects_stats; // [0..12 effect types] - std::array effects_statslast; // [0..12 effect types] - bool isMonitorEffect = false; + bool effects_active = false; //!< True if FFB is globally active. + uint32_t effects_used = 0; //!< Bitmask of effect types used since reset. + std::array effects_stats; //!< Statistics for each effect type, [0..12 effect types]. + std::array effects_statslast; //!< Statistics from the previous cycle, [0..12 effect types]. + bool isMonitorEffect = false; //!< Flag to enable effect monitoring. + + // Reconstruction filter + ReconFilterMode reconFilterMode = ReconFilterMode::NO_RECONSTRUCTION; //!< Current reconstruction filter mode. + + /** + * @brief Internal method to push a new value into the reconstruction filter. + * @param state Pointer to the reconstruction filter state. + * @param newValue The new value to push into the filter. + */ + void pushReconParam(ReconFilterState* state, float newValue); + + /** + * @brief Retrieves the value from the linear reconstruction filter. + * @param state Pointer to the reconstruction filter state. + * @param fallbackValue Value to return if the filter is not ready. + * @return The interpolated value from the filter. + */ + float getReconstructedvalue(ReconFilterState* state, float fallbackValue); + + /** + * @brief Calculates the force for a single component of an effect on a specific axis. + * Dispatches between conditional and non-conditional effects. + */ + int32_t calculateEffectForceOnAxis(FFB_Effect *effect, int32_t forceVector, std::vector> &axes, uint8_t axis); - int32_t calcComponentForce(FFB_Effect *effect, int32_t forceVector, std::vector> &axes, uint8_t axis); + /** + * @brief Calculates the base force for non-conditional effects (Constant, Ramp, Periodic). + */ int32_t calcNonConditionEffectForce(FFB_Effect* effect); + + /** + * @brief Calculates the speed threshold for friction ramp-up. + */ float speedRampupPct(); + + /** + * @brief Calculates the force for conditional effects (Spring, Damper, Inertia, Friction). + */ int32_t calcConditionEffectForce(FFB_Effect *effect, float metric, uint8_t gain, uint8_t idx, float scale, float angle_ratio); - int32_t getEnvelopeMagnitude(FFB_Effect *effect); + + /** + * @brief Calculates the magnitude of an effect with an envelope. + */ + int32_t getEnvelopeMagnitude(FFB_Effect *effect, int32_t baseMagnitude); + + /** + * @brief Generates a string listing the effects used. + */ std::string listEffectsUsed(bool details = false,uint8_t axis = 0); - //std::string listForceEffects(); + + /** + * @brief Validates and sanitizes filter coefficients. + */ void checkFilterCoeff(biquad_constant_t *filter, uint32_t freq,uint8_t q); + + /** + * @brief Updates the filters for all active effects of a specific type. + */ void updateFilterSettingsForEffects(uint8_t type_effect); }; /** * Helper interface class for common effects calculator related control functions */ +/** + * @brief Helper interface class for common effects calculator related control functions. + * This class provides a common interface for controlling FFB effects. + */ class EffectsControlItf{ public: - virtual void set_FFB(bool state) = 0; // Enables or disables FFB + /** + * @brief Enables or disables FFB. + * @param state The new state of the FFB. + */ + virtual void set_FFB(bool state) = 0; + + /** + * @brief Stops the FFB. + */ virtual void stop_FFB(){set_FFB(false);}; + + /** + * @brief Starts the FFB. + */ virtual void start_FFB(){set_FFB(true);}; + + /** + * @brief Resets all FFB effects. + */ virtual void reset_ffb() = 0; - virtual uint32_t getConstantForceRate(); // Returns an estimate of the constant force effect update rate in hz - virtual uint32_t getRate(); // Returns an estimate of the overall effect update speed in hz + + /** + * @brief Returns an estimate of the constant force effect update rate in Hz. + * @return The estimated update rate. + */ + virtual uint32_t getConstantForceRate(); + + /** + * @brief Returns an estimate of the overall effect update speed in Hz. + * @return The estimated update rate. + */ + virtual uint32_t getRate(); + + /** + * @brief Checks if FFB is active. + * @return true if FFB is active, false otherwise. + */ virtual bool getFfbActive() = 0; + + /** + * @brief Sets the global gain for all effects. + * @param gain The new gain value. + */ virtual void set_gain(uint8_t gain) = 0; + + /** + * @brief To be called when a constant force update event occurs. Used for rate calculation. + */ virtual void cfUpdateEvent(); + + /** + * @brief To be called when any FFB update event occurs. Used for rate calculation. + */ virtual void fxUpdateEvent(); + virtual void updateSamplerate(float newSamplerate) = 0; // Should be called when update loop rate is changed private: - FastMovingAverage fxPeriodAvg{20}; - FastMovingAverage cfUpdatePeriodAvg{20}; + FastMovingAverage fxPeriodAvg{5}; + FastMovingAverage cfUpdatePeriodAvg{5}; - uint32_t lastFxUpdate = 0; - uint32_t lastCfUpdate = 0; + uint32_t lastFxUpdate = 0; //!< Timestamp of the last FFB update. + uint32_t lastCfUpdate = 0; //!< Timestamp of the last constant force update. }; #endif /* EFFECTSCALCULATOR_H_ */ diff --git a/Firmware/FFBoard/Inc/Filters.h b/Firmware/FFBoard/Inc/Filters.h index 83a31bf17..92c2a7959 100644 --- a/Firmware/FFBoard/Inc/Filters.h +++ b/Firmware/FFBoard/Inc/Filters.h @@ -2,13 +2,17 @@ * Filters.h * * Created on: Feb 13, 2020 - * Author: Yannick + * Author: Yannick, Vincent */ #ifndef FILTERS_H_ #define FILTERS_H_ #include "cppmain.h" +#ifdef USE_DSP_FUNCTIONS +#include "arm_math.h" +#endif + #ifdef __cplusplus // Frequency in hz, q in float q*100. Example: Q 0.5 -> 50 @@ -40,14 +44,27 @@ class Biquad{ float getFc() const; void setQ(float Q); float getQ() const; + void setPeakGain(float peakGainDB); void calcBiquad(void); -protected: +#ifdef USE_DSP_FUNCTIONS + const float* getCoeffs() const { return pCoeffs; } +#endif +protected: BiquadType type; - float a0, a1, a2, b1, b2; float Fc, Q, peakGain; + +#ifdef USE_DSP_FUNCTIONS + // CMSIS-DSP instance + arm_biquad_casd_df1_inst_f32 S; + float32_t pCoeffs[5]; + float32_t pState[4]; // For a single biquad stage (DF1 float requires 4 states) +#else float z1, z2; + float a0, a1, a2, b1, b2; +#endif + }; diff --git a/Firmware/FFBoard/Inc/HidFFB.h b/Firmware/FFBoard/Inc/HidFFB.h index 28ddc6707..bb0d0cfcd 100644 --- a/Firmware/FFBoard/Inc/HidFFB.h +++ b/Firmware/FFBoard/Inc/HidFFB.h @@ -20,53 +20,184 @@ #define Z_AXIS_ENABLE 4 #define DIRECTION_ENABLE(AXES) (1 << AXES) +/** + * @brief This class handles the Force Feedback (FFB) HID communication. + * It inherits from UsbHidHandler to process HID reports and from EffectsControlItf to control FFB effects. + * It is responsible for parsing HID FFB reports from the host and managing the lifecycle of FFB effects. + */ class HidFFB: public UsbHidHandler, public EffectsControlItf { public: + /** + * @brief Construct a new HidFFB object. + * @param ec A shared pointer to the EffectsCalculator instance. + * @param axisCount The number of axes to be controlled. + */ HidFFB(std::shared_ptr ec,uint8_t axisCount); virtual ~HidFFB(); + /** + * @brief Handles outgoing HID reports from the host (PC -> Device). This is the main entry point for FFB commands. + * @param report_id The report ID. + * @param report_type The type of the report. + * @param buffer A pointer to the report data. + * @param bufsize The size of the report data. + * @override from UsbHidHandler + */ void hidOut(uint8_t report_id, hid_report_type_t report_type,const uint8_t* buffer, uint16_t bufsize) override; + + /** + * @brief Handles incoming HID GET_FEATURE requests from the host (Device -> PC). + * Used for status reports like block load and PID pool. + * @param report_id The report ID. + * @param report_type The type of the report. + * @param buffer A pointer to the buffer where the report data should be stored. + * @param reqlen The requested length of the report. + * @return The actual length of the report. + * @override from UsbHidHandler + */ uint16_t hidGet(uint8_t report_id, hid_report_type_t report_type,uint8_t* buffer, uint16_t reqlen) override; - bool getFfbActive(); + /** + * @brief Checks if the FFB is active. + * @return true if FFB is active, false otherwise. + * @override from EffectsControlItf + */ + bool getFfbActive() override; + + /** + * @brief Sends a HID report to the host. + * @param report A pointer to the report data. + * @param len The length of the report data. + * @return true if the report was sent successfully, false otherwise. + */ static bool HID_SendReport(uint8_t *report,uint16_t len); - void reset_ffb(); - void start_FFB(); - void stop_FFB(); - void set_FFB(bool state); - void set_gain(uint8_t gain); + /** + * @brief Resets all FFB effects. + * @override from EffectsControlItf + */ + void reset_ffb() override; + + /** + * @brief Starts the FFB. + * @override from EffectsControlItf + */ + void start_FFB() override; + + /** + * @brief Stops the FFB. + * @override from EffectsControlItf + */ + void stop_FFB() override; + + /** + * @brief Sets the FFB state (active/inactive). + * @param state The new state of the FFB. + * @override from EffectsControlItf + */ + void set_FFB(bool state) override; + + /** + * @brief Sets the global gain for all FFB effects. + * @param gain The new gain value (0-255). + * @override from EffectsControlItf + */ + void set_gain(uint8_t gain) override; + /** + * @brief Sends a status report for a specific effect to the host. + * @param effect The ID of the effect. + */ void sendStatusReport(uint8_t effect); + + /** + * @brief Sets the direction enable mask for the axes. + * This mask determines how direction parameters in HID reports are interpreted. + * @param mask The new direction enable mask. + */ void setDirectionEnableMask(uint8_t mask); + void updateSamplerate(float newSamplerate); private: - // HID - std::shared_ptr effects_calc; - std::array& effects; // Must be passed in constructor + // HID processing methods + std::shared_ptr effects_calc; //!< A shared pointer to the EffectsCalculator instance. + std::array& effects; //!< A reference to the array of FFB effects, managed by EffectsCalculator, Must be passed in constructor. + + /** + * @brief Handles the "Create New Effect" HID report. Allocates a new effect. + * @param effect Pointer to the HID report data. + */ void new_effect(FFB_CreateNewEffect_Feature_Data_t* effect); + + /** + * @brief Frees an effect slot. This is called when a HID_ID_BLKFRREP is received. + * @param id The block index of the effect to free. + */ void free_effect(uint16_t id); + + /** + * @brief Handles FFB control commands (Enable, Disable, Stop, Reset, etc.). + * @param cmd The control command byte. + */ void ffb_control(uint8_t cmd); + + /** + * @brief Handles the "Set Effect" HID report. Configures a previously created effect. + * @param effect Pointer to the HID report data. + */ void set_effect(FFB_SetEffect_t* effect); + + /** + * @brief Handles the "Set Condition" HID report (Spring, Damper, Friction, Inertia). + * @param cond Pointer to the HID report data. + */ void set_condition(FFB_SetCondition_Data_t* cond); + + /** + * @brief Handles the "Set Envelope" HID report. + * @param report Pointer to the HID report data. + */ void set_envelope(FFB_SetEnvelope_Data_t* report); + + /** + * @brief Handles the "Set Ramp" HID report. + * @param report Pointer to the HID report data. + */ void set_ramp(FFB_SetRamp_Data_t* report); + + /** + * @brief Handles the "Set Constant Force" HID report. + * @param effect Pointer to the HID report data. + */ void set_constant_effect(FFB_SetConstantForce_Data_t* effect); + + /** + * @brief Handles the "Set Periodic" HID report (Sine, Square, etc.). + * @param report Pointer to the HID report data. + */ void set_periodic(FFB_SetPeriodic_Data_t* report); - void set_effect_operation(FFB_EffOp_Data_t* report); + /** + * @brief Handles the "Effect Operation" HID report (Start, Stop, Start Solo). + * @param report Pointer to the HID report data. + */ + void set_effect_operation(FFB_EffOp_Data_t* report); + /** + * @brief Sets the default filters for a new effect based on its type. + * @param effect Pointer to the effect to configure. + */ void set_filters(FFB_Effect* effect); - uint8_t directionEnableMask; // Has to be adjusted if bit is not last bit after axis enable bits - uint16_t used_effects = 0; - bool ffb_active = false; - FFB_BlockLoad_Feature_Data_t blockLoad_report; - FFB_PIDPool_Feature_Data_t pool_report; + uint8_t directionEnableMask; //!< Mask to enable/disable directions for axes. Adjusted based on axis count. + uint16_t used_effects = 0; //!< The number of currently active effects. + bool ffb_active = false; //!< Flag indicating if FFB is globally active. + FFB_BlockLoad_Feature_Data_t blockLoad_report; //!< HID report structure for block load status. + FFB_PIDPool_Feature_Data_t pool_report; //!< HID report structure for PID pool status. - reportFFB_status_t reportFFBStatus; + reportFFB_status_t reportFFBStatus; //!< HID report structure for general FFB status. - uint8_t axisCount; + uint8_t axisCount; //!< The number of axes supported by this FFB instance. }; #endif /* HIDFFB_H_ */ diff --git a/Firmware/FFBoard/Inc/MotorDriver.h b/Firmware/FFBoard/Inc/MotorDriver.h index 0446ac3ba..b643a66ac 100644 --- a/Firmware/FFBoard/Inc/MotorDriver.h +++ b/Firmware/FFBoard/Inc/MotorDriver.h @@ -2,12 +2,14 @@ * MotorDriver.h * * Created on: Feb 1, 2020 - * Author: Yannick + * Author: Yannick, Vincent */ #ifndef MOTORDRIVER_H_ #define MOTORDRIVER_H_ +#define MAX_SLEW_RATE 65535 + #include "cppmain.h" #include "ChoosableClass.h" #include "PersistentStorage.h" @@ -25,11 +27,32 @@ class MotorDriver : public ChoosableClass{ const ClassType getClassType() override {return ClassType::Motordriver;}; static const std::vector> all_drivers; + virtual void setupDriver(); virtual void turn(int16_t power); virtual void stopMotor(); virtual void startMotor(); virtual void emergencyStop(bool reset = false); + virtual void setPowerLimit(uint16_t power){}; // specific motor driver manager power, this is used to send powerLimit to the driver, like TMC4671. + + // + /** + * Slew rate calibration interface (no-op by default) + * If driver can't calibration the max slew rate will by MAX_SLEW_RATE (65535) + * @return false is the driver not implemented this process or true if calibration start + */ + virtual bool startSlewRateCalibration() { return false; }; + /** + * Check if calibration is in process + * @return the state of calibration process + */ + virtual bool isSlewRateCalibrationInProgress() { return false; }; + /** + * Get the value of the Slew Rate after a calibration + * @return + */ + virtual uint16_t getDrvSlewRate() { return MAX_SLEW_RATE; }; + virtual bool motorReady(); // Returns true if the driver is active and ready to receive commands virtual Encoder* getEncoder(); // Encoder is managed by the motor driver. Must always return an encoder diff --git a/Firmware/FFBoard/Inc/SPI.h b/Firmware/FFBoard/Inc/SPI.h index b1a063f79..0f6afedfe 100644 --- a/Firmware/FFBoard/Inc/SPI.h +++ b/Firmware/FFBoard/Inc/SPI.h @@ -14,6 +14,7 @@ #include "SpiHandler.h" #include "semaphore.hpp" +#include struct SPIConfig { SPIConfig(OutputPin cs,bool cspol = true) @@ -77,7 +78,7 @@ class SPIPort: public SpiHandler { bool hasFreePins(); uint32_t getBaseClk(); - std::pair getClosestPrescaler(float clock); + std::pair getClosestPrescaler(float clock,float min = 0, float max = INFINITY); SPI_HandleTypeDef* getPortHandle(); diff --git a/Firmware/FFBoard/Inc/SerialFFB.h b/Firmware/FFBoard/Inc/SerialFFB.h index e16cfc1a7..9ec6e26be 100644 --- a/Firmware/FFBoard/Inc/SerialFFB.h +++ b/Firmware/FFBoard/Inc/SerialFFB.h @@ -37,6 +37,7 @@ class SerialFFB : public CommandHandler, public EffectsControlItf{ void setMagnitude(uint8_t idx,int16_t magnitude); void setEffectState(uint8_t id, bool state); + void updateSamplerate(float newSamplerate); private: static ClassIdentifier info; diff --git a/Firmware/FFBoard/Inc/SystemCommands.h b/Firmware/FFBoard/Inc/SystemCommands.h index 46ef39695..ec6118529 100644 --- a/Firmware/FFBoard/Inc/SystemCommands.h +++ b/Firmware/FFBoard/Inc/SystemCommands.h @@ -11,7 +11,7 @@ #include "CommandHandler.h" enum class FFBoardMain_commands : uint32_t{ - help=0,save=1,reboot=2,dfu=3,swver=4,hwtype=5,lsmain,main,lsactive,format,errors,errorsclr,flashdump,flashraw,vint,vext,mallinfo,heapfree,taskstats,debug,devid,uid,temp,otp,signature + help=0,save=1,reboot=2,dfu=3,swver=4,hwtype=5,lsmain,main,lsactive,format,errors,errorsclr,flashdump,flashraw,vint,vext,mallinfo,heapfree,taskstats,debug,devid,uid,temp,otp,signature,tasklist }; class SystemCommands : public CommandHandler { diff --git a/Firmware/FFBoard/Inc/constants.h b/Firmware/FFBoard/Inc/constants.h index 8f6724a9e..a80453b77 100644 --- a/Firmware/FFBoard/Inc/constants.h +++ b/Firmware/FFBoard/Inc/constants.h @@ -31,11 +31,19 @@ static const uint8_t SW_VERSION_INT[3] = {1,16,5}; // Version as array. 8 bit ea #ifdef FFBWHEEL #ifdef FFBWHEEL_USE_1AXIS_DESC +#ifdef HIDAXISRES_USE_32B_DESC +#define AXIS1_FFB_HID_DESC_32B +#else #define AXIS1_FFB_HID_DESC +#endif +#else +#ifdef HIDAXISRES_USE_32B_DESC +#define AXIS2_FFB_HID_DESC_32B #else #define AXIS2_FFB_HID_DESC #endif #endif +#endif #ifdef FFBJOYSTICK #define AXIS2_FFB_HID_DESC diff --git a/Firmware/FFBoard/Inc/cpp_target_config.h b/Firmware/FFBoard/Inc/cpp_target_config.h index fcf4f7ed6..20b898825 100644 --- a/Firmware/FFBoard/Inc/cpp_target_config.h +++ b/Firmware/FFBoard/Inc/cpp_target_config.h @@ -47,4 +47,8 @@ extern const OutputPin debugpin; extern const OutputPin gpMotor; #endif +#if defined(I2C_PORT_EEPROM) +extern I2CPort i2cport_int; +#endif + #endif diff --git a/Firmware/FFBoard/Inc/ffb_defs.h b/Firmware/FFBoard/Inc/ffb_defs.h index e78b1e6fd..ccce5f402 100644 --- a/Firmware/FFBoard/Inc/ffb_defs.h +++ b/Firmware/FFBoard/Inc/ffb_defs.h @@ -96,55 +96,96 @@ // Only include these for cpp #ifdef __cplusplus -// HID gamepad report - +template struct __attribute__((__packed__)) reportHID_t { uint8_t id = 1; uint64_t buttons = 0; +#if MAX_AXIS >= 1 + dtypeaxis X = 0; +#else int16_t X = 0; +#endif +#if MAX_AXIS >= 2 + dtypeaxis Y = 0; +#else int16_t Y = 0; +#endif +#if MAX_AXIS >= 3 + dtypeaxis Z = 0; +#else int16_t Z = 0; +#endif int16_t RX = 0; int16_t RY = 0; int16_t RZ = 0; int16_t Dial = 0; int16_t Slider = 0; }; - -/* - * Helper function to access analog axes in packed HID report struct +/** + * Helper class for double buffered HID gamepad reports to allow use of different datatypes for main axes + * Double buffer allows testing if data has changed before sending */ -inline void setHidReportAxis(reportHID_t *report, uint8_t idx, int16_t val){ - switch(idx){ - case 0: - report->X = val; - break; - case 1: - report->Y = val; - break; - case 2: - report->Z = val; - break; - case 3: - report->RX = val; - break; - case 4: - report->RY = val; - break; - case 5: - report->RZ = val; - break; - case 6: - report->Dial = val; - break; - case 7: - report->Slider = val; - break; - default: - return; +class HID_GamepadReport_base{ +public: + virtual void setHidReportAxis(uint8_t idx, uint32_t val) = 0; + virtual uint8_t* getBuffer() = 0; + virtual uint32_t getLength() = 0; + virtual uint64_t getButtons() = 0; + virtual void setButtons(uint64_t btn) = 0; //! Must use setter to prevent unaligned access + virtual bool changed() = 0; + virtual void swap() = 0; +}; + +template +class HID_GamepadReport : public HID_GamepadReport_base{ +private: + reportHID_t report1; + reportHID_t report2; + reportHID_t* report = &report1; + +public: + uint64_t getButtons() override {return report->buttons;} + void setButtons(uint64_t btn) override {report->buttons = btn;} + + void setHidReportAxis(uint8_t idx, uint32_t val) override { + switch(idx){ + case 0: + report->X = val; + break; + case 1: + report->Y = val; + break; + case 2: + report->Z = val; + break; + case 3: + report->RX = val; + break; + case 4: + report->RY = val; + break; + case 5: + report->RZ = val; + break; + case 6: + report->Dial = val; + break; + case 7: + report->Slider = val; + break; + default: + return; + } } -} + bool changed() override {return memcmp(&report1,&report2,sizeof(reportHID_t)) != 0;} + void swap() override {report = (report == &report1 ? &report2 : &report1);} // Swaps report buffers + + uint32_t getLength() override {return sizeof(reportHID_t);} + uint8_t* getBuffer() override {return reinterpret_cast(this->report);} + +}; + typedef struct { @@ -154,7 +195,25 @@ typedef struct } __attribute__((packed)) reportFFB_status_t; - +/** + * @brief Contient l'état et les tampons pour + * l'interpolation d'un seul paramètre (ex: magnitude ou offset). + */ +typedef struct +{ +#ifdef USE_DSP_FUNCTIONS + float32_t spline_x[4] = {0}; // Buffer time(en us) + float32_t spline_y[4] = {0}; // Buffer value + float32_t spline_y2[4] = {0}; // Buffer for Spline Natural + float32_t spline_scratch[8] = {0}; // Buffer for Spline Natural + arm_spline_instance_f32 spline_instance; // Instance pour CMSIS-DSP + bool spline_arm_initialized = false; // CMSIS-DSP initialized ? +#else + float spline_x[4] = {0}; // Buffer time(en us) + float spline_y[4] = {0}; // Buffer value +#endif + bool isSplineReady = false; // Le tampon est-il plein ? +} ReconFilterState; typedef struct { @@ -292,6 +351,9 @@ typedef struct uint16_t samplePeriod = 0; bool useEnvelope = false; bool useSingleCondition = true; + + ReconFilterState recon_magnitude; // State pour Magnitude (ou Amplitude) + ReconFilterState recon_offset; // State pour Offset (périodiques) } FFB_Effect; diff --git a/Firmware/FFBoard/Inc/flash_helpers.h b/Firmware/FFBoard/Inc/flash_helpers.h index a409a48fe..09fab245d 100644 --- a/Firmware/FFBoard/Inc/flash_helpers.h +++ b/Firmware/FFBoard/Inc/flash_helpers.h @@ -2,7 +2,7 @@ * flash_helpers.h * * Created on: 31.01.2020 - * Author: Yannick + * Author: Yannick, Vincent */ #ifndef FLASH_HELPERS_H_ @@ -23,6 +23,7 @@ extern "C" { #include #include +#include bool Flash_Init(); bool Flash_Write(uint16_t adr,uint16_t dat); // Writes or updates only if changed or missing @@ -31,6 +32,11 @@ bool Flash_ReadWriteDefault(uint16_t adr,uint16_t *buf,uint16_t def); // returns void Flash_Dump(std::vector> *result,bool includeAll = false); bool Flash_Format(); +#ifdef COGGING_TABLE_FLASH_START_ADDRESS +bool Flash_WriteCoggingTable(uint8_t table_idx, int16_t* data); +bool Flash_ReadCoggingTable(uint8_t table_idx, int16_t* data); +#endif + bool OTP_Write(uint16_t adroffset,uint64_t dat); bool OTP_Read(uint16_t adroffset,uint64_t* dat); @@ -58,4 +64,7 @@ inline std::tuple unpack(uint16_t v) { #endif +extern const std::span> flash_factory_defaults; // address,value pair +void Flash_Write_Defaults(); + #endif /* FLASH_HELPERS_H_ */ diff --git a/Firmware/FFBoard/Inc/ringbufferwrapper.h b/Firmware/FFBoard/Inc/ringbufferwrapper.h index 2ba46b8c8..99eef8caf 100644 --- a/Firmware/FFBoard/Inc/ringbufferwrapper.h +++ b/Firmware/FFBoard/Inc/ringbufferwrapper.h @@ -57,7 +57,7 @@ T RingBufferWrapper::peek_as(bool* ok) noexcept T data; // Only POD types can be trivially copied from // the ring buffer. - if (!std::is_pod::value) { + if (!std::is_standard_layout::value && !std::is_trivial::value) { *ok = false; return data; } diff --git a/Firmware/FFBoard/Src/AxesManager.cpp b/Firmware/FFBoard/Src/AxesManager.cpp index dd1edd726..c2855fe11 100644 --- a/Firmware/FFBoard/Src/AxesManager.cpp +++ b/Firmware/FFBoard/Src/AxesManager.cpp @@ -102,19 +102,25 @@ bool AxesManager::setAxisCount(int8_t count) { } void AxesManager::usbSuspend() { - for (auto &axis : axes) { - axis->usbSuspend(); - } + for (auto &axis : axes) { + axis->usbSuspend(); + } } void AxesManager::usbResume() { - for (auto &axis : axes) { - axis->usbResume(); - } + for (auto &axis : axes) { + axis->usbResume(); + } } void AxesManager::resetPosZero() { - for (auto &axis : axes) { - axis->setPos(0); - } + for (auto &axis : axes) { + axis->setPos(0); + } +} + +void AxesManager::updateSamplerate(float newSamplerate){ + for (auto &axis : axes) { + axis->updateSamplerate(newSamplerate); + } } diff --git a/Firmware/FFBoard/Src/Axis.cpp b/Firmware/FFBoard/Src/Axis.cpp index f5394a296..90aacf662 100644 --- a/Firmware/FFBoard/Src/Axis.cpp +++ b/Firmware/FFBoard/Src/Axis.cpp @@ -2,17 +2,33 @@ * Axis.cpp * * Created on: 31.01.2020 - * Author: Yannick + * Author: Yannick, Vincent + * */ #include "Axis.h" #include "voltagesense.h" +#include "critical.hpp" + +// Load the driver is they are declared in targer_constants.h +#ifdef TMC4671DRIVER #include "TMC4671.h" +#endif +#ifdef PWMDRIVER #include "MotorPWM.h" -#include "VescCAN.h" +#endif +#ifdef ODRIVE #include "ODriveCAN.h" +#endif +#ifdef VESC +#include "VescCAN.h" +#endif +#ifdef SIMPLEMOTION #include "MotorSimplemotion.h" +#endif +#ifdef RMDCAN #include "RmdMotorCAN.h" +#endif ////////////////////////////////////////////// /* @@ -85,39 +101,50 @@ const std::vector> Axis::axis2_drivers = /** * Axis class manages motor drivers and passes effect torque to the motor drivers */ -Axis::Axis(char axis,volatile Control_t* control) :CommandHandler("axis", CLSID_AXIS), drv_chooser(MotorDriver::all_drivers),enc_chooser{Encoder::all_encoders} +Axis::Axis(char axis,volatile Control_t* control) :CommandHandler("axis", CLSID_AXIS), driverChooser(MotorDriver::all_drivers),encoderChooser{Encoder::all_encoders} { + +#ifdef USE_DSP_FUNCTIONS + speedLimiterPID.Kp = speedLimiterP; + speedLimiterPID.Ki = speedLimiterI; + speedLimiterPID.Kd = 0.0f; + arm_pid_init_f32(&speedLimiterPID, 1); +#endif + this->axis = axis; this->control = control; if (axis == 'X') { - drv_chooser = ClassChooser(axis1_drivers); + driverChooser = ClassChooser(axis1_drivers); setInstance(0); - this->flashAddrs = AxisFlashAddrs({ADR_AXIS1_CONFIG, ADR_AXIS1_MAX_SPEED, ADR_AXIS1_MAX_ACCEL, + this->flashAddresses = AxisFlashAddresses({ADR_AXIS1_CONFIG, ADR_AXIS1_MAX_SPEED, ADR_AXIS1_MAX_ACCEL, ADR_AXIS1_MAX_SLEWRATE_DRV, ADR_AXIS1_ENDSTOP, ADR_AXIS1_POWER, ADR_AXIS1_DEGREES,ADR_AXIS1_EFFECTS1,ADR_AXIS1_EFFECTS2,ADR_AXIS1_ENC_RATIO, ADR_AXIS1_SPEEDACCEL_FILTER,ADR_AXIS1_POSTPROCESS1}); } else if (axis == 'Y') { - drv_chooser = ClassChooser(axis2_drivers); + driverChooser = ClassChooser(axis2_drivers); setInstance(1); - this->flashAddrs = AxisFlashAddrs({ADR_AXIS2_CONFIG, ADR_AXIS2_MAX_SPEED, ADR_AXIS2_MAX_ACCEL, + this->flashAddresses = AxisFlashAddresses({ADR_AXIS2_CONFIG, ADR_AXIS2_MAX_SPEED, ADR_AXIS2_MAX_ACCEL, ADR_AXIS2_MAX_SLEWRATE_DRV, ADR_AXIS2_ENDSTOP, ADR_AXIS2_POWER, ADR_AXIS2_DEGREES,ADR_AXIS2_EFFECTS1,ADR_AXIS2_EFFECTS2, ADR_AXIS2_ENC_RATIO, ADR_AXIS2_SPEEDACCEL_FILTER,ADR_AXIS2_POSTPROCESS1}); } else if (axis == 'Z') { setInstance(2); - this->flashAddrs = AxisFlashAddrs({ADR_AXIS3_CONFIG, ADR_AXIS3_MAX_SPEED, ADR_AXIS3_MAX_ACCEL, + this->flashAddresses = AxisFlashAddresses({ADR_AXIS3_CONFIG, ADR_AXIS3_MAX_SPEED, ADR_AXIS3_MAX_ACCEL, ADR_AXIS3_MAX_SLEWRATE_DRV, ADR_AXIS3_ENDSTOP, ADR_AXIS3_POWER, ADR_AXIS3_DEGREES,ADR_AXIS3_EFFECTS1,ADR_AXIS3_EFFECTS2,ADR_AXIS3_ENC_RATIO, ADR_AXIS3_SPEEDACCEL_FILTER,ADR_AXIS3_POSTPROCESS1}); } + // Initialize equalizer filters + /*for (uint8_t idx = 0; idx < num_eq_bands; idx++) { + eqFilters[idx].setBiquad(BiquadType::peak, eq_frequencies[idx] / filter_f, 1.0, 0.0); + }*/ - restoreFlash(); // Load parameters CommandHandler::registerCommands(); // Internal commands registerCommands(); - updateTorqueScaler(); // In case no flash setting has been loaded yet + restoreFlash(); // Load parameters } Axis::~Axis() @@ -144,7 +171,7 @@ void Axis::registerCommands(){ registerCommand("drvtype", Axis_commands::drvtype, "Motor driver type get/set/list",CMDFLAG_GET | CMDFLAG_SET | CMDFLAG_INFOSTRING); registerCommand("pos", Axis_commands::pos, "Encoder position",CMDFLAG_GET); registerCommand("maxspeed", Axis_commands::maxspeed, "Speed limit in deg/s",CMDFLAG_GET | CMDFLAG_SET); - registerCommand("maxtorquerate", Axis_commands::maxtorquerate, "Torque rate limit in counts/ms",CMDFLAG_GET | CMDFLAG_SET); + registerCommand("slewrate", Axis_commands::slewrate, "Torque rate limit in counts/ms",CMDFLAG_GET | CMDFLAG_SET); registerCommand("fxratio", Axis_commands::fxratio, "Effect ratio. Reduces game effects excluding endstop. 255=100%",CMDFLAG_GET | CMDFLAG_SET); registerCommand("curtorque", Axis_commands::curtorque, "Axis torque",CMDFLAG_GET); registerCommand("curpos", Axis_commands::curpos, "Axis position",CMDFLAG_GET); @@ -165,10 +192,10 @@ void Axis::registerCommands(){ * Read parameters from flash and restore settings */ void Axis::restoreFlash(){ - //NormalizedAxis::restoreFlash(); + // TODO: This seems to be a remnant of a previous architecture (NormalizedAxis). Confirm and remove. // read all constants uint16_t value; - if (Flash_Read(flashAddrs.config, &value)){ + if (Flash_Read(flashAddresses.config, &value)){ this->conf = Axis::decodeConfFromInt(value); }else{ pulseErrLed(); @@ -177,57 +204,65 @@ void Axis::restoreFlash(){ setDrvType(this->conf.drvtype); setEncType(this->conf.enctype); - if (Flash_Read(flashAddrs.maxSpeed, &value)){ + if (Flash_Read(flashAddresses.maxSpeed, &value)){ this->maxSpeedDegS = value; }else{ pulseErrLed(); } -// -// if (Flash_Read(flashAddrs.maxAccel, &value)){ -// this->maxTorqueRateMS = value; -// }else{ -// pulseErrLed(); -// } - - - uint16_t esval, power; - if(Flash_Read(flashAddrs.endstop, &esval)) { - fx_ratio_i = esval & 0xff; - endstopStrength = (esval >> 8) & 0xff; + + // save the max torque for the slew rate + if (Flash_Read(flashAddresses.maxAccel, &value)){ + this->maxTorqueRateMS = value; + }else{ + pulseErrLed(); + } + + // save the max torque for the slew rate + if (Flash_Read(flashAddresses.maxSlewRateDrv, &value)){ + this->maxSlewRate_Driver = value; + }else{ + pulseErrLed(); + } + + + uint16_t endstopRawValue, power; + if(Flash_Read(flashAddresses.endstop, &endstopRawValue)) { + setEffectRatio(endstopRawValue & 0xff); + endstopStrength = (endstopRawValue >> 8) & 0xff; } - if(Flash_Read(flashAddrs.power, &power)){ + if(Flash_Read(flashAddresses.power, &power)){ setPower(power); } - uint16_t deg_t; - if(Flash_Read(flashAddrs.degrees, °_t)){ - this->degreesOfRotation = deg_t & 0x7fff; - this->invertAxis = (deg_t >> 15) & 0x1; + uint16_t degreesRawValue; + if(Flash_Read(flashAddresses.degrees, °reesRawValue)){ + this->degreesOfRotation = degreesRawValue & 0x7fff; + this->invertAxis = (degreesRawValue >> 15) & 0x1; setDegrees(degreesOfRotation); } uint16_t effects; - if(Flash_Read(flashAddrs.effects1, &effects)){ + if(Flash_Read(flashAddresses.effects1, &effects)){ setIdleSpringStrength(effects & 0xff); setFxStrengthAndFilter((effects >> 8) & 0xff,damperIntensity,damperFilter); }else{ - setIdleSpringStrength(idlespringstrength); // Use default + setIdleSpringStrength(idleSpringStrength); // Use default } - if(Flash_Read(flashAddrs.effects2, &effects)){ + if(Flash_Read(flashAddresses.effects2, &effects)){ setFxStrengthAndFilter(effects & 0xff,frictionIntensity,frictionFilter); setFxStrengthAndFilter((effects >> 8) & 0xff,inertiaIntensity,inertiaFilter); } uint16_t ratio; - if(Flash_Read(flashAddrs.encoderRatio, &ratio)){ + if(Flash_Read(flashAddresses.encoderRatio, &ratio)){ setGearRatio(ratio & 0xff, (ratio >> 8) & 0xff); } uint16_t filterStorage; - if (Flash_Read(flashAddrs.speedAccelFilter, &filterStorage)) + if (Flash_Read(flashAddresses.speedAccelFilter, &filterStorage)) { uint8_t profile = filterStorage & 0xFF; this->filterProfileId = profile; @@ -238,31 +273,32 @@ void Axis::restoreFlash(){ } uint16_t pp1; - if(Flash_Read(flashAddrs.postprocess1, &pp1)){ + if(Flash_Read(flashAddresses.postprocess1, &pp1)){ setExpo((int8_t)(pp1 & 0xff)); } } // Saves parameters to flash. void Axis::saveFlash(){ - //NormalizedAxis::saveFlash(); - Flash_Write(flashAddrs.config, Axis::encodeConfToInt(this->conf)); - Flash_Write(flashAddrs.maxSpeed, this->maxSpeedDegS); -// Flash_Write(flashAddrs.maxAccel, (uint16_t)(this->maxTorqueRateMS)); - - Flash_Write(flashAddrs.endstop, fx_ratio_i | (endstopStrength << 8)); - Flash_Write(flashAddrs.power, power); - Flash_Write(flashAddrs.degrees, (degreesOfRotation & 0x7fff) | (invertAxis << 15)); - Flash_Write(flashAddrs.effects1, idlespringstrength | (damperIntensity << 8)); - Flash_Write(flashAddrs.effects2, frictionIntensity | (inertiaIntensity << 8)); - Flash_Write(flashAddrs.encoderRatio, gearRatio.numerator | (gearRatio.denominator << 8)); + // TODO: This seems to be a remnant of a previous architecture (NormalizedAxis). Confirm and remove. + Flash_Write(flashAddresses.config, Axis::encodeConfToInt(this->conf)); + Flash_Write(flashAddresses.maxSpeed, this->maxSpeedDegS); + Flash_Write(flashAddresses.maxAccel, (uint16_t)(this->maxTorqueRateMS)); + Flash_Write(flashAddresses.maxSlewRateDrv, (uint16_t)(this->maxSlewRate_Driver)); + + Flash_Write(flashAddresses.endstop, effectRatio | (endstopStrength << 8)); + Flash_Write(flashAddresses.power, power); + Flash_Write(flashAddresses.degrees, (degreesOfRotation & 0x7fff) | (invertAxis << 15)); + Flash_Write(flashAddresses.effects1, idleSpringStrength | (damperIntensity << 8)); + Flash_Write(flashAddresses.effects2, frictionIntensity | (inertiaIntensity << 8)); + Flash_Write(flashAddresses.encoderRatio, gearRatio.numerator | (gearRatio.denominator << 8)); // save CF biquad uint16_t filterStorage = (uint16_t)this->filterProfileId & 0xFF; - Flash_Write(flashAddrs.speedAccelFilter, filterStorage); + Flash_Write(flashAddresses.speedAccelFilter, filterStorage); // Postprocessing - Flash_Write(flashAddrs.postprocess1, expoValInt & 0xff); + Flash_Write(flashAddresses.postprocess1, expoValue & 0xff); } @@ -282,8 +318,9 @@ uint8_t Axis::getEncType(){ void Axis::setPos(uint16_t val) { startForceFadeIn(0.25,0.5); - if(this->drv != nullptr){ - drv->getEncoder()->setPos(val); + Encoder* enc_p = getEncoder(); + if(enc_p != nullptr){ + enc_p->setPos(val); } } @@ -292,6 +329,7 @@ MotorDriver* Axis::getDriver(){ } Encoder* Axis::getEncoder(){ + if(!drv) return nullptr; return drv->getEncoder(); } @@ -304,9 +342,10 @@ void Axis::prepareForUpdate(){ return; } + // TODO: The motorReady() check was commented out. Review if this is still the desired behavior or if it should be restored. //if (!drv->motorReady()) return; - float angle = getEncAngle(this->drv->getEncoder()); + float angle = getEncAngle(getEncoder()); // Scale encoder value to set rotation range // Update a change of range only when new range is within valid range @@ -336,6 +375,7 @@ void Axis::prepareForUpdate(){ }else if(abs(scaledEnc) <= 0x7fff) { outOfBounds = false; + // TODO: This error clearing seems to have been moved to the errorCallback. Confirm this is correct and remove this line. //ErrorHandler::clearError(outOfBoundsError); } @@ -347,6 +387,7 @@ void Axis::prepareForUpdate(){ this->updateMetrics(angle); + //this->updateHandsOffState(); } @@ -371,17 +412,11 @@ void Axis::updateDriveTorque(){ void Axis::setPower(uint16_t power) { this->power = power; - updateTorqueScaler(); -#ifdef TMC4671DRIVER - // Update hardware limits for TMC for safety - TMC4671 *drv = dynamic_cast(this->drv.get()); + torqueScaler = ((float)power / (float)0x7fff); if (drv != nullptr) { - //tmclimits.pid_uq_ud = power; - //tmclimits.pid_torque_flux = power; - drv->setTorqueLimit(power); + drv->setPowerLimit(power); } -#endif } @@ -390,29 +425,27 @@ void Axis::setPower(uint16_t power) */ void Axis::setDrvType(uint8_t drvtype) { - if (!drv_chooser.isValidClassId(drvtype)) + if (!driverChooser.isValidClassId(drvtype)) { return; } - this->drv.reset(nullptr); - MotorDriver* drv = drv_chooser.Create((uint16_t)drvtype); + cpp_freertos::CriticalSection::Enter(); + this->drv.reset(driverChooser.Create((uint16_t)drvtype)); if (drv == nullptr) { + cpp_freertos::CriticalSection::Exit(); return; } - this->drv = std::unique_ptr(drv); this->conf.drvtype = drvtype; + this->maxTorqueRateMS = drv->getDrvSlewRate(); // Pass encoder to driver again if(!this->drv->hasIntegratedEncoder()){ this->drv->setEncoder(this->enc); } -#ifdef TMC4671DRIVER - if (dynamic_cast(drv)) - { - setupTMC4671(); - } -#endif + + drv->setupDriver(); + if (!tud_connected()) { control->usb_disabled = false; @@ -422,27 +455,9 @@ void Axis::setDrvType(uint8_t drvtype) { drv->startMotor(); } + cpp_freertos::CriticalSection::Exit(); } -#ifdef TMC4671DRIVER -// Special tmc setup methods -void Axis::setupTMC4671() -{ - TMC4671 *drv = static_cast(this->drv.get()); -// drv->setAxis(axis); - drv->setExternalEncoderAllowed(true); - drv->restoreFlash(); - tmclimits.pid_torque_flux = getPower(); - drv->setLimits(tmclimits); - //drv->setBiquadTorque(TMC4671Biquad(tmcbq_500hz_07q_25k)); - - - // Enable driver - - drv->setMotionMode(MotionMode::torque); - drv->Start(); // Start thread -} -#endif /** @@ -450,18 +465,18 @@ void Axis::setupTMC4671() */ void Axis::setEncType(uint8_t enctype) { - if (enc_chooser.isValidClassId(enctype) && !drv->hasIntegratedEncoder()) + if (encoderChooser.isValidClassId(enctype) && !drv->hasIntegratedEncoder()) { this->conf.enctype = (enctype); - this->enc = std::shared_ptr(enc_chooser.Create(enctype)); // Make new encoder + this->enc = std::shared_ptr(encoderChooser.Create(enctype)); // Make new encoder if(drv && !drv->hasIntegratedEncoder()) this->drv->setEncoder(this->enc); }else{ this->conf.enctype = 0; // None encoder } - float angle = getEncAngle(this->drv->getEncoder()); + float angle = getEncAngle(this->getEncoder()); //int32_t scaledEnc = scaleEncValue(angle, degreesOfRotation); // reset metrics this->resetMetrics(angle); @@ -549,26 +564,26 @@ metric_t* Axis::getMetrics() { } /** - * Returns position as 16b int scaled to gamepad range + * Returns position as int scaled to gamepad range */ int32_t Axis::getLastScaledEnc() { - return clip(metric.current.pos,-0x7fff,0x7fff); + return clip(metric.current.pos_f * 0x7fffffff,-0x7fffffff,0x7fffffff); // Calc from float pos } /** * Changes intensity of idle spring when FFB is off */ int32_t Axis::updateIdleSpringForce() { - return clip((int32_t)(-metric.current.pos*idlespringscale),-idlespringclip,idlespringclip); + return clip((int32_t)(-metric.current.pos_scaled_16b*idleSpringScale),-idleSpringClip,idleSpringClip); } /* * Set the strength of the spring effect if FFB is disabled */ void Axis::setIdleSpringStrength(uint8_t spring){ - idlespringstrength = spring; - idlespringclip = clip((int32_t)spring*35,0,10000); - idlespringscale = 0.5f + ((float)spring * 0.01f); + idleSpringStrength = spring; + idleSpringClip = clip((int32_t)spring*35,0,10000); + idleSpringScale = 0.5f + ((float)spring * 0.01f); } /** @@ -582,26 +597,27 @@ void Axis::setFxStrengthAndFilter(uint8_t val,uint8_t& valToSet, Biquad& filter) } /** - * Called before HID effects are calculated - * Should calculate always on and idle effects specific to the axis like idlespring and friction + * Calculates the internal mechanical effects (damper, friction, inertia) that are always active. + * Called before HID effects are calculated. + * Also calculates idle spring when FFB is inactive. */ -void Axis::calculateAxisEffects(bool ffb_on){ - axisEffectTorque = 0; +void Axis::calculateMechanicalEffects(bool ffb_on){ + mechanicalEffectTorque = 0; if(!ffb_on){ - axisEffectTorque += updateIdleSpringForce(); + mechanicalEffectTorque += updateIdleSpringForce(); } // Always active damper if(damperIntensity != 0){ float speedFiltered = (metric.current.speed) * (float)damperIntensity * AXIS_DAMPER_RATIO; - axisEffectTorque -= damperFilter.process(clip(speedFiltered, -intFxClip, intFxClip)); + mechanicalEffectTorque -= damperFilter.process(clip(speedFiltered, -internalFxClip, internalFxClip)); } // Always active inertia if(inertiaIntensity != 0){ float accelFiltered = metric.current.accel * (float)inertiaIntensity * AXIS_INERTIA_RATIO; - axisEffectTorque -= inertiaFilter.process(clip(accelFiltered, -intFxClip, intFxClip)); + mechanicalEffectTorque -= inertiaFilter.process(clip(accelFiltered, -internalFxClip, internalFxClip)); } // Always active friction. Based on effectsCalculator implementation @@ -610,12 +626,17 @@ void Axis::calculateAxisEffects(bool ffb_on){ float speedRampupCeil = 4096; float rampupFactor = 1.0; if (fabs (speed) < speedRampupCeil) { // if speed in the range to rampup we apply a sine curve - float phaseRad = M_PI * ((fabs (speed) / speedRampupCeil) - 0.5);// we start to compute the normalized angle (speed / normalizedSpeed@5%) and translate it of -1/2PI to translate sin on 1/2 periode - rampupFactor = ( 1 + sin(phaseRad ) ) / 2; // sin value is -1..1 range, we translate it to 0..2 and we scale it by 2 +#ifdef USE_DSP_FUNCTIONS + float phaseRad = PI * ((fabsf (speed) / speedRampupCeil) - 0.5f);// we start to compute the normalized angle (speed / normalizedSpeed@5%) and translate it of -1/2PI to translate sin on 1/2 periode + rampupFactor = ( 1.0f + arm_sin_f32(phaseRad ) ) / 2.0f; // sin value is -1..1 range, we translate it to 0..2 and we scale it by 2 +#else + float phaseRad = M_PI * ((fabsf (speed) / speedRampupCeil) - 0.5f);// we start to compute the normalized angle (speed / normalizedSpeed@5%) and translate it of -1/2PI to translate sin on 1/2 periode + rampupFactor = ( 1.0f + sinf(phaseRad ) ) / 2.0f; // sin value is -1..1 range, we translate it to 0..2 and we scale it by 2 +#endif } int8_t sign = speed >= 0 ? 1 : -1; float force = (float)frictionIntensity * rampupFactor * sign * INTERNAL_AXIS_FRICTION_SCALER * 32; - axisEffectTorque -= frictionFilter.process(clip(force, -intFxClip, intFxClip)); + mechanicalEffectTorque -= frictionFilter.process(clip(force, -internalFxClip, internalFxClip)); } } @@ -623,9 +644,9 @@ void Axis::calculateAxisEffects(bool ffb_on){ /** * Changes the ratio of effects to endstop strength. 255 = same strength, 0 = no effects */ -void Axis::setFxRatio(uint8_t val) { - fx_ratio_i = val; - updateTorqueScaler(); +void Axis::setEffectRatio(uint8_t val) { + effectRatio = val; + effectRatioScaler = ((float)effectRatio/255.0); } /** @@ -634,11 +655,15 @@ void Axis::setFxRatio(uint8_t val) { void Axis::resetMetrics(float new_pos= 0) { // pos is degrees metric.current = metric_t(); metric.current.posDegrees = new_pos; - std::tie(metric.current.pos,metric.current.pos_f) = scaleEncValue(new_pos, degreesOfRotation); + std::tie(metric.current.pos_scaled_16b,metric.current.pos_f) = scaleEncValue(new_pos, degreesOfRotation); metric.previous = metric_t(); // Reset filters speedFilter.calcBiquad(); accelFilter.calcBiquad(); + +#ifdef USE_DSP_FUNCTIONS + arm_pid_reset_f32(&speedLimiterPID); // reset the PID limit +#endif } /** @@ -649,14 +674,14 @@ void Axis::updateMetrics(float new_pos) { // pos is degrees metric.previous = metric.current; metric.current.posDegrees = new_pos; - std::tie(metric.current.pos,metric.current.pos_f) = scaleEncValue(new_pos, degreesOfRotation); + std::tie(metric.current.pos_scaled_16b,metric.current.pos_f) = scaleEncValue(new_pos, degreesOfRotation); // compute speed and accel from raw instant speed normalized - float currentSpeed = (new_pos - metric.previous.posDegrees) * 1000.0; // deg/s + float currentSpeed = (new_pos - metric.previous.posDegrees) * this->filter_f; // deg/s metric.current.speed = speedFilter.process(currentSpeed); - metric.current.accel = accelFilter.process((currentSpeed - _lastSpeed))* 1000.0; // deg/s/s - _lastSpeed = currentSpeed; + metric.current.accel = accelFilter.process((currentSpeed - previousFrameSpeed))* this->filter_f; // deg/s/s + previousFrameSpeed = currentSpeed; } @@ -667,7 +692,7 @@ uint16_t Axis::getPower(){ } /** - * Calculates an exponential torque correction curve + * Calculates an exponential torque correction curve and scale for FFBEffect */ int32_t Axis::calculateExpoTorque(int32_t torque){ float torquef = (float)torque / (float)0x7fff; // This down and upscaling may introduce float artifacts. Do this before scaling down. @@ -678,17 +703,17 @@ int32_t Axis::calculateExpoTorque(int32_t torque){ } } -void Axis::updateTorqueScaler() { - effect_margin_scaler = ((float)fx_ratio_i/255.0); - torqueScaler = ((float)power / (float)0x7fff); -} +int64_t Axis::calculateFFBTorque() { -float Axis::getTorqueScaler(){ - return torqueScaler; -} + int64_t torque = this->ffbEffectTorque; + + // Compute scaler + torque *= effectRatioScaler; + return torque * 0x7fff; +} -int32_t Axis::getTorque() { return metric.current.torque; } +int32_t Axis::getTorque() { return metric.current.torque; } // Fix: move from previous to current bool Axis::isInverted() { return invertAxis; @@ -697,20 +722,21 @@ bool Axis::isInverted() { /** * Calculate soft endstop effect */ -int16_t Axis::updateEndstop(){ - int8_t clipdir = cliptest(metric.current.pos, -0x7fff, 0x7fff); - if(clipdir == 0){ +int32_t Axis::calculateEndstopTorque(){ + // TODO Check the type int8_t and the range clipping is -0x7fff..0x7fff + int8_t clipDirection = cliptest(metric.current.pos_scaled_16b, -0x7fff, 0x7fff); + if(clipDirection == 0){ return 0; } - float addtorque = clipdir*metric.current.posDegrees - (float)this->degreesOfRotation/2.0; // degress of rotation counts total range so multiply by 2 - addtorque *= (float)endstopStrength * endstopGain; // Apply endstop gain for stiffness. - addtorque *= -clipdir; + float endstopTorque = clipDirection*metric.current.posDegrees - (float)this->degreesOfRotation/2.0; // degress of rotation counts total range so multiply by 2 + endstopTorque *= (float)endstopStrength * endstopGain; // Apply endstop gain for stiffness. + endstopTorque *= -clipDirection; - return clip(addtorque,-0x7fff,0x7fff); + return clip(endstopTorque,-0x7fff,0x7fff); } -void Axis::setEffectTorque(int32_t torque) { - effectTorque = torque; +void Axis::setFfbEffectTorque(int64_t torque) { + this->ffbEffectTorque = torque; } /** pass in ptr to receive the sum of the effects + endstop torque @@ -719,81 +745,138 @@ void Axis::setEffectTorque(int32_t torque) { bool Axis::updateTorque(int32_t* totalTorque) { - if(abs(effectTorque) >= 0x7fff){ - pulseClipLed(); + // Step 1: Process FFB torque from the game (via helper function) + int64_t torque = calculateFFBTorque(); + + // Step 2: Add internal torque effects + torque += mechanicalEffectTorque; // Add locally calculated effects (damper, friction, inertia). + torque += calculateEndstopTorque(); // Add endstop force if the axis reaches its rotation limits. + + // Step 3: Apply safety and comfort limiters + torque -= applySpeedLimiterTorque(torque); // apply speedLimiter + applyTorqueSlewRateLimiter(torque); // Torque Slew Rate Limiter: + + // Cut torque if the encoder is out of bounds (safety) or hands are off. + //if(outOfBounds || handsOff){ + if(outOfBounds){ + torque = 0; } - // Scale effect torque - int32_t torque = effectTorque; // Game effects - if(expo != 1){ - torque = calculateExpoTorque(torque); + // Apply a fade-in effect for a smooth force ramp-up on startup. + if(forceFadeMultiplier < 1){ + torque = torque * forceFadeMultiplier; + forceFadeMultiplier += forceFadeDuration / this->filter_f; // Fade time } - torque *= effect_margin_scaler; - torque += axisEffectTorque; // Independent effects - torque += updateEndstop(); - torque *= torqueScaler; // Scale to power + // Step 4: Prepare the final torque for the driver. + torque *= torqueScaler; // Apply the main power setting ("force volume"). + torque = (invertAxis) ? -torque : torque; // Invert axis if required. - // TODO speed and accel limiters - if(maxSpeedDegS > 0){ + // clip and alert clipping + int32_t torqueAfterClipping = clip(torque, -power, power); + if (torqueAfterClipping != torque){ + pulseClipLed(); + } - float torqueSign = torque > 0 ? 1 : -1; // Used to prevent metrics against the force to go into the limiter - // Speed. Mostly tuned... - //spdlimiterAvg.addValue(metric.current.speed); - float speedreducer = (float)((metric.current.speed*torqueSign) - (float)maxSpeedDegS) * ((float)0x7FFF / maxSpeedDegS); - spdlimitreducerI = clip( spdlimitreducerI + ((speedreducer * speedLimiterI) * torqueScaler),0,power); + // Store the actually applied torque for the next iteration (used by the slew rate limiter). + metric.current.torque = torqueAfterClipping; - // Accel limit. Not really useful. Maybe replace with torque slew rate limit? -// float accreducer = (float)((metric.current.accel*torqueSign) - (float)maxAccelDegSS) * getAccelScalerNormalized(); -// acclimitreducerI = clip( acclimitreducerI + ((accreducer * 0.02) * torqueScaler),0,power); + // return result + *totalTorque = torqueAfterClipping; + return (metric.current.torque != metric.previous.torque); +} - // Only reduce torque. Don't invert it to prevent oscillation - float torqueReduction = speedreducer * speedLimiterP + spdlimitreducerI;// accreducer * 0.025 + acclimitreducerI - if(torque > 0){ - torqueReduction = clip(torqueReduction,0,torque); - }else{ - torqueReduction = clip(-torqueReduction,torque,0); +void Axis::applyTorqueSlewRateLimiter(int64_t& torque) +{ + // Limits the rate of change of the torque (slew rate), to smooths out sudden changes in torque. + // Essential for a natural feel and to prevent "clanking" noises. + if(maxTorqueRateMS == 0) { + return; // Limiter is disabled + } + + // This prevents sudden torque jumps, resulting in a smoother feel. + const int64_t previousTorque = metric.previous.torque; + const int64_t maxTorqueChange = maxTorqueRateMS; + + // The torque is clipped to be within the range of [previous torque - limit, previous torque + limit]. + torque = clip(torque, previousTorque - maxTorqueChange, previousTorque + maxTorqueChange); } - torque -= torqueReduction; - } - // Torque slew rate limiter - if(maxTorqueRateMS > 0){ - torque = clip(torque, metric.previous.torque - maxTorqueRateMS,metric.previous.torque + maxTorqueRateMS); - } -// if(torque - metric.previous.torque) - if(outOfBounds){ - torque = 0; - } +int64_t Axis::applySpeedLimiterTorque(int64_t& torque){ + // Speed Limiter: A PI controller to reduce torque when speed exceeds maxSpeedDegS. + // The limiter only acts when torque is applied in the direction of movement. - // Fade in - if(forceFadeCurMult < 1){ - torque = torque * forceFadeCurMult; - forceFadeCurMult += forceFadeTime / this->filter_f; // Fade time + // if limiter is disabled, return + if(maxSpeedDegS <= 0) { + return 0; } - // Torque calculated. Now sending to driver - torque = (invertAxis) ? -torque : torque; - metric.current.torque = torque; - torque = clip(torque, -power, power); - - bool torqueChanged = metric.current.torque != metric.previous.torque; + int64_t resultTorque = 0; - if (abs(torque) == power){ - pulseClipLed(); +#ifdef USE_DSP_FUNCTIONS + float effectiveSpeed = metric.current.speed * (torque > 0 ? 1.0f : -1.0f); + if (effectiveSpeed > maxSpeedDegS) + { + // --- PI Controller Logic --- + // 1. Calculate the error term (how much we are over the speed limit). + float speedError = effectiveSpeed - maxSpeedDegS; + + // 2. Calculate the total reduction amount using the PID controller. + float reductionAmount = arm_pid_f32(&speedLimiterPID, speedError); + + // 3. Apply the reduction to the main torque. + // We must only reduce the magnitude of the torque, not invert it. + reductionAmount = clip(reductionAmount, 0.0f, fabsf((float)torque)); + if(torque > 0) { + resultTorque = reductionAmount; + } else { + resultTorque = -reductionAmount; + } + } else { + arm_pid_reset_f32(&speedLimiterPID); // Reset PID if not active } +#else + float torqueSign = torque > 0 ? 1 : -1; // Used to prevent metrics against the force to go into the limiter + // Speed. Mostly tuned... + //spdlimiterAvg.addValue(metric.current.speed); + float speedreducer = (float)((metric.current.speed*torqueSign) - (float)maxSpeedDegS) * ((float)0x7FFF / maxSpeedDegS); + speedLimitReducerI = clip( speedLimitReducerI + ((speedreducer * speedLimiterI) * torqueScaler),0,power); + + // Only reduce torque. Don't invert it to prevent oscillation + float torqueReduction = speedreducer * speedLimiterP + speedLimitReducerI;// accreducer * 0.025 + acclimitreducerI + if(torque > 0){ + resultTorque = clip(torqueReduction,0,torque); + }else{ + resultTorque = clip(-torqueReduction,torque,0); + } +#endif - *totalTorque = torque; - return (torqueChanged); + return resultTorque; +} + +void Axis::updateSamplerate(float newSamplerate){ + this->filter_f = newSamplerate; + this->updateFilters(this->filterProfileId); // Recalculate filters +} + +void Axis::updateFilters(uint8_t profileId){ + this->filterProfileId = profileId; + speedFilter.setFc(filterSpeedCst[this->filterProfileId].freq / filter_f); + speedFilter.setQ(filterSpeedCst[this->filterProfileId].q / 100.0); + accelFilter.setFc(filterAccelCst[this->filterProfileId].freq / filter_f); + accelFilter.setQ(filterAccelCst[this->filterProfileId].q / 100.0); + damperFilter.setFc(filterDamperCst.freq/filter_f); + inertiaFilter.setFc(filterInertiaCst.freq/filter_f); + frictionFilter.setFc(filterFrictionCst.freq/filter_f); } /** * Starts fading in force from start to 1 over fadeTime */ void Axis::startForceFadeIn(float start,float fadeTime){ - this->forceFadeTime = fadeTime; - this->forceFadeCurMult = clip(start, 0, 1); + this->forceFadeDuration = fadeTime; + this->forceFadeMultiplier = clip(start, 0, 1); } @@ -804,9 +887,9 @@ void Axis::setDegrees(uint16_t degrees){ degrees &= 0x7fff; if(degrees == 0){ - nextDegreesOfRotation = lastdegreesOfRotation; + nextDegreesOfRotation = previousDegreesOfRotation; }else{ - lastdegreesOfRotation = degreesOfRotation; + previousDegreesOfRotation = degreesOfRotation; nextDegreesOfRotation = degrees; } } @@ -814,7 +897,7 @@ void Axis::setDegrees(uint16_t degrees){ void Axis::setExpo(int val){ val = clip(val, -127, 127); - expoValInt = val; + expoValue = val; if(val == 0){ expo = 1; // Explicitly force expo off return; @@ -844,14 +927,6 @@ CommandStatus Axis::command(const ParsedCommand& cmd,std::vector& case Axis_commands::degrees: handleGetSetFunc(cmd, replies, degreesOfRotation, &Axis::setDegrees,this); -// if (cmd.type == CMDtype::get) -// { -// replies.emplace_back(degreesOfRotation); -// } -// else if (cmd.type == CMDtype::set) -// { -// setDegrees(cmd.val); -// } break; case Axis_commands::esgain: @@ -877,7 +952,7 @@ CommandStatus Axis::command(const ParsedCommand& cmd,std::vector& case Axis_commands::idlespring: if (cmd.type == CMDtype::get) { - replies.emplace_back(idlespringstrength); + replies.emplace_back(idleSpringStrength); } else if (cmd.type == CMDtype::set) { @@ -920,7 +995,7 @@ CommandStatus Axis::command(const ParsedCommand& cmd,std::vector& case Axis_commands::enctype: if(cmd.type == CMDtype::info){ - enc_chooser.replyAvailableClasses(replies,this->getEncType()); + encoderChooser.replyAvailableClasses(replies,this->getEncType()); }else if(cmd.type == CMDtype::get){ replies.emplace_back(this->getEncType()); }else if(cmd.type == CMDtype::set){ @@ -930,7 +1005,7 @@ CommandStatus Axis::command(const ParsedCommand& cmd,std::vector& case Axis_commands::drvtype: if(cmd.type == CMDtype::info){ - drv_chooser.replyAvailableClasses(replies,this->getDrvType()); + driverChooser.replyAvailableClasses(replies,this->getDrvType()); }else if(cmd.type == CMDtype::get){ replies.emplace_back(this->getDrvType()); }else if(cmd.type == CMDtype::set){ @@ -939,14 +1014,14 @@ CommandStatus Axis::command(const ParsedCommand& cmd,std::vector& break; case Axis_commands::pos: - if (cmd.type == CMDtype::get && this->drv->getEncoder() != nullptr) + if (cmd.type == CMDtype::get && getEncoder() != nullptr) { - int32_t pos = this->drv->getEncoder()->getPos(); + int32_t pos = getEncoder()->getPos(); replies.emplace_back(isInverted() ? -pos : pos); } - else if (cmd.type == CMDtype::set && this->drv->getEncoder() != nullptr) + else if (cmd.type == CMDtype::set && getEncoder() != nullptr) { - this->drv->getEncoder()->setPos(isInverted() ? -cmd.val : cmd.val); + getEncoder()->setPos(isInverted() ? -cmd.val : cmd.val); } else { @@ -958,29 +1033,60 @@ CommandStatus Axis::command(const ParsedCommand& cmd,std::vector& handleGetSet(cmd, replies, this->maxSpeedDegS); break; - case Axis_commands::maxtorquerate: - handleGetSet(cmd, replies, this->maxTorqueRateMS); + case Axis_commands::slewrate: + { + if(cmd.type == CMDtype::get){ + // If driver has a more restrictive calibrated value, update the axis limit + if(maxSlewRate_Driver < this->maxTorqueRateMS) { + this->maxTorqueRateMS = maxSlewRate_Driver; + } + replies.emplace_back(this->maxTorqueRateMS); + }else if(cmd.type == CMDtype::set){ + this->maxTorqueRateMS = clip(cmd.val, 0, maxSlewRate_Driver); + } + } + break; + + case Axis_commands::calibrate_maxSlewRateDrv: + { + if(cmd.type == CMDtype::get){ + // Start calibration on driver and set awaiting flag if start is OK + if (drv->startSlewRateCalibration()) { + this->awaitingSlewCalibration = true; + } else { + // Inform user that calibration can't started + CommandHandler::broadcastCommandReply(CommandReply("Slew rate calibration unsupported",1), (uint32_t)Axis_commands::calibrate_maxSlewRateDrv, CMDtype::get); + } + replies.emplace_back(1); // ack + } + break; + } + + case Axis_commands::maxSlewRateDrv: + if (cmd.type == CMDtype::get) { + replies.emplace_back(maxSlewRate_Driver); + } break; case Axis_commands::fxratio: if(cmd.type == CMDtype::get){ - replies.emplace_back(this->fx_ratio_i); + replies.emplace_back(this->effectRatio); }else if(cmd.type == CMDtype::set){ - setFxRatio(cmd.val); + setEffectRatio(cmd.val); } break; case Axis_commands::curpos: - replies.emplace_back(this->metric.current.pos); + replies.emplace_back(this->metric.previous.pos_scaled_16b); break; case Axis_commands::curtorque: - replies.emplace_back(this->metric.current.torque); + replies.emplace_back(getTorque()); break; case Axis_commands::curspd: - replies.emplace_back(this->metric.current.speed); + replies.emplace_back(this->metric.previous.speed); break; case Axis_commands::curaccel: - replies.emplace_back(this->metric.current.accel); + replies.emplace_back(this->metric.previous.accel); break; case Axis_commands::reductionScaler: @@ -999,11 +1105,7 @@ CommandStatus Axis::command(const ParsedCommand& cmd,std::vector& else if (cmd.type == CMDtype::set) { uint32_t value = clip(cmd.val, 0, filterSpeedCst.size()-1); - this->filterProfileId = value; - speedFilter.setFc(filterSpeedCst[this->filterProfileId].freq / filter_f); - speedFilter.setQ(filterSpeedCst[this->filterProfileId].q / 100.0); - accelFilter.setFc(filterAccelCst[this->filterProfileId].freq / filter_f); - accelFilter.setQ(filterAccelCst[this->filterProfileId].q / 100.0); + this->updateFilters(value); } break; case Axis_commands::filterSpeed: @@ -1024,9 +1126,10 @@ CommandStatus Axis::command(const ParsedCommand& cmd,std::vector& if (cmd.type == CMDtype::get) { uint32_t cpr = 0; - if(this->drv->getEncoder() != nullptr){ - cpr = this->drv->getEncoder()->getCpr(); + if(this->getEncoder() != nullptr){ + cpr = this->getEncoder()->getCpr(); } + // TODO: For TMC4671 drivers, CPR reporting might be inconsistent. Investigate if a prescale is needed or if the UI should handle the readout correction. //#ifdef TMC4671DRIVER // CPR should be consistent with position. Maybe change TMC to prescale to encoder count or correct readout in UI // TMC4671 *tmcdrv = dynamic_cast(this->drv.get()); // Special case for TMC. Get the actual encoder resolution // if (tmcdrv && tmcdrv->hasIntegratedEncoder()) @@ -1041,7 +1144,7 @@ CommandStatus Axis::command(const ParsedCommand& cmd,std::vector& break; case Axis_commands::expo: - handleGetSetFunc(cmd, replies, expoValInt, &Axis::setExpo, this); // need to also provide the expoScaler constant + handleGetSetFunc(cmd, replies, expoValue, &Axis::setExpo, this); // need to also provide the expoScaler constant break; case Axis_commands::exposcale: diff --git a/Firmware/FFBoard/Src/CmdParser.cpp b/Firmware/FFBoard/Src/CmdParser.cpp index 73640b9fd..bd61b1206 100644 --- a/Firmware/FFBoard/Src/CmdParser.cpp +++ b/Firmware/FFBoard/Src/CmdParser.cpp @@ -155,8 +155,8 @@ bool CmdParser::parse(std::vector& commands){ // Check if conversion is even possible bool validPqm = (pqm != std::string::npos && (std::isdigit(word[pqm+1]) || (std::isdigit(word[pqm+2]) && (word[pqm+1] == '-' || word[pqm+1] == '+')) || ( std::isxdigit(word[pqm+2]) && word[pqm+1] == 'x'))); bool validPeq = (peq != std::string::npos && (std::isdigit(word[peq+1]) || (std::isdigit(word[peq+2]) && (word[peq+1] == '-' || word[peq+1] == '+')) || ( std::isxdigit(word[peq+2]) && word[peq+1] == 'x'))); - - if(validPqm && validPeq && peq < pqm && (abs(pqm - peq) > 1)){ // =? + int32_t pqm_peq_dist = (pqm - peq); + if(validPqm && validPeq && peq < pqm && (abs(pqm_peq_dist) > 1)){ // =? // Dual int64_t val; int64_t val2; @@ -167,9 +167,9 @@ bool CmdParser::parse(std::vector& commands){ } if(word[peq+1] == 'x'){ - val = (int64_t)std::strtoll(word.substr(peq+2, pqm-peq).c_str(),0,16); + val = (int64_t)std::strtoll(word.substr(peq+2, pqm_peq_dist).c_str(),0,16); }else{ - val = (int64_t)std::strtoll(word.substr(peq+1, pqm-peq).c_str(),0,10); + val = (int64_t)std::strtoll(word.substr(peq+1, pqm_peq_dist).c_str(),0,10); } cmdstring = word.substr(cmd_start, peq-cmd_start); diff --git a/Firmware/FFBoard/Src/CommandHandler.cpp b/Firmware/FFBoard/Src/CommandHandler.cpp index ae7c3fcbc..95cf4d823 100644 --- a/Firmware/FFBoard/Src/CommandHandler.cpp +++ b/Firmware/FFBoard/Src/CommandHandler.cpp @@ -12,6 +12,7 @@ #include "CDCcomm.h" //#include #include "ChoosableClass.h" +#include //std::vector CommandHandler::cmdHandlers; //std::set CommandHandler::cmdHandlerIDs; @@ -522,3 +523,39 @@ void CommandHandler::removeCommandHandler(){ removeCallbackHandler(getCommandHandlers(), this); //cmdHandlerListMutex.Unlock(); } + +/** + * Registers a new command. Called by registerCommand template + */ +void CommandHandler::registerCommand_INT(const char* cmd,const uint32_t cmdid,const char* help,uint32_t flags){ + for(auto it = registeredCommands.begin();it!=registeredCommands.end();++it){ + CmdHandlerCommanddef& cmdDef = *it; + if(cmdDef.cmdId == cmdid){ + if(cmdDef.flags & CMDFLAG_EXTOVERRIDE){ + // Override dummy present. Only update other data if not present and honor flag mask + flags &= flags | CMDFLAG_EXTOVERRIDE; + registeredCommands.erase(it); // Remove old dummy + break; + }else{ + return; //already present + } + } + } + + this->registeredCommands.emplace_back(cmd, help,cmdid,flags); + this->registeredCommands.shrink_to_fit(); +} + +/** + * Adds an override dummy or changes flags of a command. Called by template. TODO untested + */ +void CommandHandler::overrideCommandFlags_INT(const uint32_t cmdid,uint32_t flagmask){ + for(CmdHandlerCommanddef& cmdDef : registeredCommands){ + if(cmdDef.cmdId == static_cast(cmdid)){ + cmdDef.flags &= flagmask; + cmdDef.flags |= CMDFLAG_EXTOVERRIDE; + return; //already present + } + } + this->registeredCommands.emplace_back(nullptr, nullptr,cmdid,flagmask); // Dummy +} diff --git a/Firmware/FFBoard/Src/CommandInterface.cpp b/Firmware/FFBoard/Src/CommandInterface.cpp index 9aa004c91..0427cd0d0 100644 --- a/Firmware/FFBoard/Src/CommandInterface.cpp +++ b/Firmware/FFBoard/Src/CommandInterface.cpp @@ -240,7 +240,7 @@ void StringCommandInterface::generateReplyFromCmd(std::string& replyPart,const P */ -CDC_CommandInterface::CDC_CommandInterface() : StringCommandInterface(1024), Thread("CDCCMD", 512, 37) { +CDC_CommandInterface::CDC_CommandInterface() : StringCommandInterface(CDC_CMD_BUFFER_SIZE), Thread("CDCCMD", 512, 37) { parser.setClearBufferTimeout(parserTimeout); this->Start(); } diff --git a/Firmware/FFBoard/Src/EffectsCalculator.cpp b/Firmware/FFBoard/Src/EffectsCalculator.cpp index 688afb25f..18fb6ed4f 100644 --- a/Firmware/FFBoard/Src/EffectsCalculator.cpp +++ b/Firmware/FFBoard/Src/EffectsCalculator.cpp @@ -11,6 +11,9 @@ #include "Axis.h" #include "ledEffects.h" +#ifdef USE_DSP_FUNCTIONS +#include "arm_math.h" +#endif #define EFFECT_STATE_INACTIVE 0 @@ -49,6 +52,7 @@ EffectsCalculator::EffectsCalculator() : CommandHandler("fx", CLSID_EFFECTSCALC) registerCommand("filterProfile_id", EffectsCalculator_commands::filterProfileId, "Conditional effects filter profile: 0 default; 1 custom", CMDFLAG_GET | CMDFLAG_SET); registerCommand("frictionPctSpeedToRampup", EffectsCalculator_commands::frictionPctSpeedToRampup, "% of max speed for gradual increase", CMDFLAG_GET | CMDFLAG_SET); + registerCommand("reconFilterMode", EffectsCalculator_commands::reconFilterMode, "Recon. filter: 0=None, 1=Linear, 2=CubicNatural, 3=CubicHermite", CMDFLAG_GET | CMDFLAG_SET); //this->Start(); // Enable if we want to periodically monitor } @@ -74,6 +78,15 @@ void EffectsCalculator::setActive(bool active) setClipLed(active); } +void EffectsCalculator::updateSamplerate(float newSamplerate){ + this->calcfrequency = newSamplerate; + for(FFB_Effect &effect : this->effects){ + if(effect.filter[0]){ // Update filters if effect has filters + setFilters(&effect); + } + } +} + /* If the metric is less than CP Offset - Dead Band, then the resulting force is given by the following formula: @@ -87,6 +100,136 @@ An inertia condition uses axis acceleration as the metric. */ +float EffectsCalculator::getReconstructedvalue(ReconFilterState* state, float fallbackValue) +{ + // 'reconFilterMode' est une variable membre de la classe + + float resulting_value = fallbackValue; // Par défaut, valeur "NONE" + uint32_t now_us = micros(); + float last_known_time = state->spline_x[3]; // Le point le plus récent + + // Timeout de 50ms (si le jeu est en pause, etc.) + if (!state->isSplineReady || (now_us > last_known_time + 50000)) { + return state->spline_y[3]; // Maintenir la dernière valeur + } + + switch(reconFilterMode) { + case ReconFilterMode::NO_RECONSTRUCTION: + resulting_value = state->spline_y[3]; // La plus récente (pas de filtre) + break; + + case ReconFilterMode::LINEAR_INTERPOLATION: + { + // "Safe" Linear Interpolation (Delayed by 1 sample) + // To absolutely guarantee NO OVERSHOOT, we must not extrapolate. + // We accept a strictly defined transport delay of 1 sample. + // + // Logic: We are currently at time 'now_us', which is AFTER the latest update 't1'. + // We don't know the future, so we replay the ramp from V0 to V1, but we start it NOW. + // We use the previous interval duration (t1 - t0) as our best guess for when the + // NEXT packet (t2) will arrive, ensuring we reach V1 exactly when t2 is expected. + + float t0 = state->spline_x[2]; // Time of penultimate sample (T-1) + float t1 = state->spline_x[3]; // Time of latest sample (T) + float v0 = state->spline_y[2]; // Value of penultimate sample (V0) + float v1 = state->spline_y[3]; // Value of latest sample (V1) + + // Estimate the expected duration until the next packet arrives. + float expected_interval = t1 - t0; + + // Sanity check: avoid division by zero if updates are too fast (e.g. double-send bugs) + if (expected_interval < 1.0f) { + resulting_value = v1; + break; + } + + // Calculate progress based on time elapsed SINCE t1. + float time_since_t1 = (float)(now_us - t1); + float progress = time_since_t1 / expected_interval; + + // Clamp progress to [0.0, 1.0] to eliminate ANY overshoot. + progress = clip(progress, 0.0f, 1.0f); + + // Interpolate between the two KNOWN, SAFE past values. + resulting_value = v0 + progress * (v1 - v0); + break; + } + +#ifdef USE_DSP_FUNCTIONS + // if DSP is enabled we have SPLINE available, else use Hermite + case ReconFilterMode::SPLINE_CUBIC_NATURAL: + { + // If spline is not ready, return last known value + if (!state->spline_arm_initialized) { + resulting_value = state->spline_y[3]; + break; + } + + float32_t interpolated_torque_f = 0.0f; + float32_t now_f = (float)now_us; + + // Clamp time to known range to avoid extrapolation + float32_t interp_time = clip(now_f, state->spline_x[0], state->spline_x[3]); + + // Perform the spline interpolation using CMSIS-DSP + arm_spline_f32(&state->spline_instance, &interp_time, &interpolated_torque_f, 1); + + // Return the interpolated value + resulting_value = interpolated_torque_f; + break; + } +#endif + + case ReconFilterMode::SPLINE_CUBIC_HERMITE: +#ifndef USE_DSP_FUNCTIONS + // if the DSP is not available, we use Hermite for spline + case ReconFilterMode::SPLINE_CUBIC_NATURAL: +#endif + { + // Interpolation hermit is made betwwen P1 (idx 1) and P2 (idx 2) + const float p1 = state->spline_y[1]; + const float p2 = state->spline_y[2]; + const float t1 = state->spline_x[1]; + const float t2 = state->spline_x[2]; + + // sanity check to not divide by zero and clamp for not overshoot + float interval = t2 - t1; + if (interval <= 0) { + resulting_value = p1; + break; + } + float t = ((float)now_us - t1) / interval; + t = clip(t, 0.0f, 1.0f); + + // Tangentes (Catmull-Rom) + float m1, m2; + float dt_m1 = state->spline_x[2] - state->spline_x[0]; + float dt_m2 = state->spline_x[3] - state->spline_x[1]; + + // Compute tangents safely + if (dt_m1 > 0) m1 = (state->spline_y[2] - state->spline_y[0]) / dt_m1; else m1 = 0; + if (dt_m2 > 0) m2 = (state->spline_y[3] - state->spline_y[1]) / dt_m2; else m2 = 0; + + // Scale tangents by interval + m1 *= interval; + m2 *= interval; + + // Hermite basis functions + float tSq = t * t; + float tCub = tSq * t; + float h_00 = 2*tCub - 3*tSq + 1; + float h_10 = tCub - 2*tSq + t; + float h_01 = -2*tCub + 3*tSq; + float h_11 = tCub - tSq; + + // Final interpolation + resulting_value = h_00 * p1 + h_10 * m1 + h_01 * p2 + h_11 * m2; + break; + } + } + return resulting_value; +} + /** * Calculates the resulting torque for FFB effects * Takes current position input scaled from -0x7fff to 0x7fff @@ -94,67 +237,59 @@ An inertia condition uses axis acceleration as the metric. */ void EffectsCalculator::calculateEffects(std::vector> &axes) { - for (auto &axis : axes) { - axis->setEffectTorque(0); - axis->calculateAxisEffects(isActive()); - } - - if(!isActive()){ - return; - } - - int32_t force = 0; int axisCount = axes.size(); - int32_t forces[MAX_AXIS] = {0}; + int64_t forces[MAX_AXIS] = {0}; - for (uint8_t i = 0; i < effects_stats.size(); i++) - { - effects_stats[i].current = {0}; // Reset active effect forces - } + if(isActive()){ + int32_t force = 0; + for (uint8_t i = 0; i < effects_stats.size(); i++) + { + effects_stats[i].current = {0}; // Reset active effect forces + } - for (uint8_t fxi = 0; fxi < MAX_EFFECTS; fxi++) - { - FFB_Effect *effect = &effects[fxi]; + for (uint8_t fxi = 0; fxi < MAX_EFFECTS; fxi++) + { + FFB_Effect *effect = &effects[fxi]; - // Effect activated and not infinite (0 or 0xffff) - if (effect->state != EFFECT_STATE_INACTIVE && effect->duration != FFB_EFFECT_DURATION_INFINITE && effect->duration != 0){ - // Start delay not yet reached - if(HAL_GetTick() < effect->startTime){ - continue; + // Effect activated and not infinite (0 or 0xffff) + if (effect->state != EFFECT_STATE_INACTIVE && effect->duration != FFB_EFFECT_DURATION_INFINITE && effect->duration != 0){ + // Start delay not yet reached + if(HAL_GetTick() < effect->startTime){ + continue; + } + // If effect has expired make inactive + if (HAL_GetTick() - effect->startTime > effect->duration) + { + effect->state = EFFECT_STATE_INACTIVE; + for(uint8_t axis=0 ; axis < axisCount ; axis++) + calcStatsEffectType(effect->type, 0,axis); // record a 0 on the ended force + } } - // If effect has expired make inactive - if (HAL_GetTick() - effect->startTime > effect->duration) + + // Filter out inactive effects + if (effect->state == EFFECT_STATE_INACTIVE) { - effect->state = EFFECT_STATE_INACTIVE; - for(uint8_t axis=0 ; axis < axisCount ; axis++) - calcStatsEffectType(effect->type, 0,axis); // record a 0 on the ended force + continue; } - } - // Filter out inactive effects - if (effect->state == EFFECT_STATE_INACTIVE) - { - continue; - } + force = calcNonConditionEffectForce(effect); // Compute the effect force - force = calcNonConditionEffectForce(effect); - - for(uint8_t axis=0 ; axis < axisCount ; axis++) // Calculate effects for all axes - { - int32_t axisforce = calcComponentForce(effect, force, axes, axis); - calcStatsEffectType(effect->type, axisforce,axis); - forces[axis] += axisforce; // Do not clip yet to allow effects to subtract force correctly. Will not overflow as maxeffects * 0x7fff is less than int32 range + for(uint8_t axis=0 ; axis < axisCount ; axis++) // Calculate effects for all axes + { + int32_t axisforce = calculateEffectForceOnAxis(effect, force, axes, axis); + calcStatsEffectType(effect->type, axisforce,axis); + forces[axis] += axisforce; // Do not clip yet to allow effects to subtract force correctly. Will not overflow as maxeffects * 0x7fff is less than int32 range + } } + effects_statslast = effects_stats; } // Apply summed force to axes for(uint8_t i=0 ; i < axisCount ; i++) { - int32_t force = clip(forces[i], -0x7fff, 0x7fff); // Clip - axes[i]->setEffectTorque(force); + axes[i]->calculateMechanicalEffects(isActive()); + axes[i]->setFfbEffectTorque(forces[i]); } - - effects_statslast = effects_stats; } /** @@ -162,13 +297,40 @@ void EffectsCalculator::calculateEffects(std::vector> &axe * Periodic and constant effects */ int32_t EffectsCalculator::calcNonConditionEffectForce(FFB_Effect *effect) { - int32_t force_vector = 0; - int32_t magnitude = effect->magnitude; - // If using an envelope modulate the magnitude based on time - if(effect->useEnvelope){ - magnitude = getEnvelopeMagnitude(effect); + // Sanity check effect type must be non-conditional + // Avoid calculating reconstructed forces for conditional effects here + if (effect->type == FFB_EFFECT_SPRING || + effect->type == FFB_EFFECT_DAMPER || + effect->type == FFB_EFFECT_FRICTION || + effect->type == FFB_EFFECT_INERTIA) { + return 0; } + + int32_t force_vector = 0; + + // Get interpolated magnitude (or amplitude) + float interpolated_magnitude = getReconstructedvalue( + &effect->recon_magnitude, // Use the new structure + (float)effect->magnitude // Fallback value (for NONE mode) + ); + + // Get interpolated offset + float interpolated_offset_float = getReconstructedvalue( + &effect->recon_offset, // Use the new structure + (float)effect->offset // Fallback value (for NONE mode) + ); + int32_t offset_lrf = (int32_t)interpolated_offset_float; + + // Magnitude with envelope if used + int32_t magnitude; + if(effect->useEnvelope){ + magnitude = getEnvelopeMagnitude(effect, (int32_t)interpolated_magnitude); + } else { + magnitude = (int32_t)interpolated_magnitude; + } + + switch (effect->type){ case FFB_EFFECT_CONSTANT: @@ -179,34 +341,34 @@ int32_t EffectsCalculator::calcNonConditionEffectForce(FFB_Effect *effect) { case FFB_EFFECT_RAMP: { - uint32_t elapsed_time = HAL_GetTick() - effect->startTime; + float elapsed_time = (micros()/1000.0) - (float)effect->startTime; int32_t duration = effect->duration; - force_vector = (int32_t)effect->startLevel + ((int32_t)elapsed_time * (effect->endLevel - effect->startLevel)) / duration; + force_vector = (int32_t)effect->startLevel + (elapsed_time * (effect->endLevel - effect->startLevel)) / duration; break; } case FFB_EFFECT_SQUARE: { - uint32_t elapsed_time = HAL_GetTick() - effect->startTime; + uint32_t elapsed_time = HAL_GetTick() - effect->startTime; // Square is ms aligned int32_t force = ((elapsed_time + effect->phase) % ((uint32_t)effect->period + 2)) < (uint32_t)(effect->period + 2) / 2 ? -magnitude : magnitude; - force_vector = force + effect->offset; + force_vector = force + offset_lrf; break; } case FFB_EFFECT_TRIANGLE: { int32_t force = 0; - int32_t offset = effect->offset; - uint32_t elapsed_time = HAL_GetTick() - effect->startTime; + int32_t offset = offset_lrf; + float elapsed_time = micros() - ((float)effect->startTime*1000.0); uint32_t phase = effect->phase; uint32_t period = effect->period; float periodF = period; int32_t maxMagnitude = offset + magnitude; int32_t minMagnitude = offset - magnitude; - uint32_t phasetime = (phase * period) / 35999; - uint32_t timeTemp = elapsed_time + phasetime; - float remainder = timeTemp % period; + float phasetime = (phase * period) / 35999.0; + uint32_t timeTemp = elapsed_time + (phasetime*1000); // timetemp in µs + float remainder = (timeTemp % (period*1000)) / 1000; float slope = ((maxMagnitude - minMagnitude) * 2) / periodF; if (remainder > (periodF / 2)) force = slope * (periodF - remainder); @@ -219,17 +381,17 @@ int32_t EffectsCalculator::calcNonConditionEffectForce(FFB_Effect *effect) { case FFB_EFFECT_SAWTOOTHUP: { - float offset = effect->offset; - uint32_t elapsed_time = HAL_GetTick() - effect->startTime; + float offset = offset_lrf; + float elapsed_time = micros() - ((float)effect->startTime*1000.0); uint32_t phase = effect->phase; uint32_t period = effect->period; float periodF = effect->period; float maxMagnitude = offset + magnitude; float minMagnitude = offset - magnitude; - int32_t phasetime = (phase * period) / 35999; - uint32_t timeTemp = elapsed_time + phasetime; - float remainder = timeTemp % period; + float phasetime = (phase * period) / 35999.0; + uint32_t timeTemp = elapsed_time + (phasetime*1000); // timetemp in µs + float remainder = (timeTemp % (period*1000)) / 1000; float slope = (maxMagnitude - minMagnitude) / periodF; force_vector = (int32_t)(minMagnitude + slope * (period - remainder)); break; @@ -237,17 +399,17 @@ int32_t EffectsCalculator::calcNonConditionEffectForce(FFB_Effect *effect) { case FFB_EFFECT_SAWTOOTHDOWN: { - float offset = effect->offset; - uint32_t elapsed_time = HAL_GetTick() - effect->startTime; + float offset = offset_lrf; + float elapsed_time = micros() - ((float)effect->startTime*1000.0); float phase = effect->phase; uint32_t period = effect->period; float periodF = effect->period; float maxMagnitude = offset + magnitude; float minMagnitude = offset - magnitude; - int32_t phasetime = (phase * period) / 35999; - uint32_t timeTemp = elapsed_time + phasetime; - float remainder = timeTemp % period; + float phasetime = (phase * period) / 35999.0; + uint32_t timeTemp = elapsed_time + (phasetime*1000); // timetemp in µs + float remainder = (timeTemp % (period*1000)) / 1000; float slope = (maxMagnitude - minMagnitude) / periodF; force_vector = (int32_t)(minMagnitude + slope * (remainder)); // reverse time break; @@ -255,11 +417,15 @@ int32_t EffectsCalculator::calcNonConditionEffectForce(FFB_Effect *effect) { case FFB_EFFECT_SINE: { - float t = HAL_GetTick() - effect->startTime; + float t = (micros()/1000.0) - (float)effect->startTime; float freq = 1.0f / (float)(std::max(effect->period, 2)); float phase = (float)effect->phase / (float)35999; //degrees - float sine = sinf(2.0 * M_PI * (t * freq + phase)) * magnitude; - force_vector = (int32_t)(effect->offset + sine); +#ifdef USE_DSP_FUNCTIONS + float sine = arm_sin_f32(2.0f * PI * (t * freq + phase)) * magnitude; +#else + float sine = sinf(2.0f * M_PI * (t * freq + phase)) * magnitude; +#endif + force_vector = (int32_t)(offset_lrf + sine); break; } default: @@ -273,10 +439,15 @@ int32_t EffectsCalculator::calcNonConditionEffectForce(FFB_Effect *effect) { /** - * Calculates the force of an effect + * @brief Calculates the final force of a single effect on a specific axis. + * It applies directional scaling and computes conditional effects (spring, damper, etc.) based on the axis's metrics. + * @param effect The effect to calculate. + * @param forceVector The base force from a non-conditional calculation (e.g., sine wave value). + * @param axes The list of all axes. + * @param axis The index of the axis to calculate the force for. + * @return The calculated torque for the axis. */ - -int32_t EffectsCalculator::calcComponentForce(FFB_Effect *effect, int32_t forceVector, std::vector> &axes, uint8_t axis) +int32_t EffectsCalculator::calculateEffectForceOnAxis(FFB_Effect *effect, int32_t forceVector, std::vector> &axes, uint8_t axis) { int32_t result_torque = 0; // uint16_t direction; @@ -313,7 +484,7 @@ int32_t EffectsCalculator::calcComponentForce(FFB_Effect *effect, int32_t forceV case FFB_EFFECT_SPRING: { - float pos = metrics->pos; + float pos = metrics->pos_scaled_16b; result_torque -= calcConditionEffectForce(effect, pos, gain.spring, con_idx, scaler.spring, angle_ratio); break; } @@ -351,9 +522,13 @@ int32_t EffectsCalculator::calcComponentForce(FFB_Effect *effect, int32_t forceV float rampupFactor = 1.0; if (fabs (speed) < speedRampupCeil) { // if speed in the range to rampup we apply a sinus curbe to ramup - float phaseRad = M_PI * ((fabs (speed) / speedRampupCeil) - 0.5);// we start to compute the normalized angle (speed / normalizedSpeed@5%) and translate it of -1/2PI to translate sin on 1/2 periode - rampupFactor = ( 1 + sin(phaseRad ) ) / 2; // sin value is -1..1 range, we translate it to 0..2 and we scale it by 2 - +#ifdef USE_DSP_FUNCTIONS + float phaseRad = PI * ((fabsf (speed) / speedRampupCeil) - 0.5f);// we start to compute the normalized angle (speed / normalizedSpeed@5%) and translate it of -1/2PI to translate sin on 1/2 periode + rampupFactor = ( 1.0f + arm_sin_f32(phaseRad ) ) / 2.0f; // sin value is -1..1 range, we translate it to 0..2 and we scale it by 2 +#else + float phaseRad = M_PI * ((fabsf (speed) / speedRampupCeil) - 0.5f);// we start to compute the normalized angle (speed / normalizedSpeed@5%) and translate it of -1/2PI to translate sin on 1/2 periode + rampupFactor = ( 1.0f + sinf(phaseRad ) ) / 2.0f; // sin value is -1..1 range, we translate it to 0..2 and we scale it by 2 +#endif } int8_t sign = speed >= 0 ? 1 : -1; @@ -438,12 +613,12 @@ int32_t EffectsCalculator::calcConditionEffectForce(FFB_Effect *effect, float m * until the fade time where the strength changes to the fade level until the stop time of the effect. * Infinite effects can't have an envelope and return the normal magnitude. */ -int32_t EffectsCalculator::getEnvelopeMagnitude(FFB_Effect *effect) +int32_t EffectsCalculator::getEnvelopeMagnitude(FFB_Effect *effect, int32_t baseMagnitude) { if(effect->duration == FFB_EFFECT_DURATION_INFINITE || effect->duration == 0){ return effect->magnitude; // Effect is infinite. envelope is invalid } - int32_t scaler = abs(effect->magnitude); + int32_t scaler = abs(baseMagnitude); uint32_t elapsed_time = HAL_GetTick() - effect->startTime; if (elapsed_time < effect->attackTime && effect->attackTime != 0) { @@ -457,7 +632,7 @@ int32_t EffectsCalculator::getEnvelopeMagnitude(FFB_Effect *effect) scaler /= (int32_t)effect->fadeTime; scaler += effect->fadeLevel; } - scaler = signbit(effect->magnitude) ? -scaler : scaler; // Follow original sign of magnitude because envelope has no sign (important for constant force) + scaler = signbit(baseMagnitude) ? -scaler : scaler; // Follow original sign of magnitude because envelope has no sign (important for constant force) return scaler; } @@ -507,6 +682,66 @@ void EffectsCalculator::setFilters(FFB_Effect *effect){ } } +void EffectsCalculator::pushReconParam(ReconFilterState* state, float newValue) +{ + uint32_t now_us = micros(); + + // Shift the spline points + for (int i = 0; i < 3; ++i) { + state->spline_x[i] = state->spline_x[i + 1]; + state->spline_y[i] = state->spline_y[i + 1]; + } + + // Add the new point + state->spline_x[3] = (float)now_us; + state->spline_y[3] = newValue; + + // FIll in initial points if not ready yet at 60Hz, so 16.66ms intervals + if (!state->isSplineReady) { + float fake_time_step = 16666.0f; // 60Hz + state->spline_x[0] = state->spline_x[3] - 3.0f * fake_time_step; + state->spline_y[0] = state->spline_y[3]; + state->spline_x[1] = state->spline_x[3] - 2.0f * fake_time_step; + state->spline_y[1] = state->spline_y[3]; + state->spline_x[2] = state->spline_x[3] - 1.0f * fake_time_step; + state->spline_y[2] = state->spline_y[3]; + state->isSplineReady = true; // Ready after first fill + } + + // Initialize spline if needed + if (reconFilterMode == ReconFilterMode::SPLINE_CUBIC_NATURAL) { +#ifdef USE_DSP_FUNCTIONS + arm_spline_init_f32( + &state->spline_instance, + ARM_SPLINE_NATURAL, + state->spline_x, + state->spline_y, + 4, + state->spline_y2, + state->spline_scratch + ); + + state->spline_arm_initialized = true; + +#endif + } +} + +void EffectsCalculator::pushReconFilterValue(FFB_Effect* effect, float new_magnitude, float new_offset, bool is_periodic) +{ + // Update target variables (for NONE mode and fallback) + effect->magnitude = (int16_t)new_magnitude; + + // Push new magnitude into recon structure + pushReconParam(&effect->recon_magnitude, new_magnitude); + + // Push new offset into recon structure if periodic + if (is_periodic) { + effect->offset = (int16_t)new_offset; + pushReconParam(&effect->recon_offset, new_offset); + } +} + void EffectsCalculator::setGain(uint8_t gain) { @@ -515,8 +750,6 @@ void EffectsCalculator::setGain(uint8_t gain) uint8_t EffectsCalculator::getGain() { return global_gain; } - - /* * Read parameters from flash and restore settings */ @@ -569,6 +802,11 @@ void EffectsCalculator::restoreFlash() frictionPctSpeedToRampup = (effects & 0xff); } + // Read reconstruction parameters + if(Flash_Read(ADR_FFB_RECONSTRUCTION_FILTER, &effects)){ + reconFilterMode = (ReconFilterMode)(effects & 0x03); + } + } // Saves parameters to flash @@ -609,6 +847,9 @@ void EffectsCalculator::saveFlash() effects = frictionPctSpeedToRampup | (filterProfileId << 8); Flash_Write(ADR_FFB_EFFECTS3, effects); + // Save reconstruction parameters + effects = (uint16_t)(reconFilterMode); + Flash_Write(ADR_FFB_RECONSTRUCTION_FILTER, effects); } void EffectsCalculator::checkFilterCoeff(biquad_constant_t *filter, uint32_t freq,uint8_t q) @@ -669,12 +910,12 @@ void EffectsCalculator::logEffectState(uint8_t type,uint8_t state){ } -void EffectsCalculator::calcStatsEffectType(uint8_t type, int16_t force,uint8_t axis){ +void EffectsCalculator::calcStatsEffectType(uint8_t type, int32_t force,uint8_t axis){ if(axis >= MAX_AXIS) return; if(type > 0 && type < 13) { uint8_t arrayLocation = type - 1; - effects_stats[arrayLocation].current[axis] = clip(effects_stats[arrayLocation].current[axis] + force, -0x7fff, 0x7fff); + effects_stats[arrayLocation].current[axis] = clip(effects_stats[arrayLocation].current[axis] + force, -0x7fff, 0x7fff); effects_stats[arrayLocation].max[axis] = std::max(effects_stats[arrayLocation].max[axis], (int16_t)abs(force)); } } @@ -934,6 +1175,15 @@ CommandStatus EffectsCalculator::command(const ParsedCommand& cmd,std::vector(cmd.val, 0, 3); + reconFilterMode = (ReconFilterMode)mode; + } + break; + default: return CommandStatus::NOT_FOUND; } @@ -1001,12 +1251,12 @@ int32_t EffectsCalculator::find_free_effect(uint8_t type){ */ uint32_t EffectsControlItf::getRate(){ float periodAvg = fxPeriodAvg.getAverage(); - if((HAL_GetTick() - lastFxUpdate) > 1000 || periodAvg == 0){ + if((micros() - lastFxUpdate) > 1000000 || periodAvg == 0){ // Reset average fxPeriodAvg.clear(); return 0; }else{ - return (1000.0/periodAvg); + return (1000000.0/periodAvg); } } @@ -1015,22 +1265,22 @@ uint32_t EffectsControlItf::getRate(){ */ uint32_t EffectsControlItf::getConstantForceRate(){ float periodAvg = cfUpdatePeriodAvg.getAverage(); - if((HAL_GetTick() - lastCfUpdate) > 1000 || periodAvg == 0){ + if((micros() - lastCfUpdate) > 1000000 || periodAvg == 0){ // Reset average cfUpdatePeriodAvg.clear(); return 0; }else{ - return (1000.0/periodAvg); + return (1000000.0/periodAvg); } } void EffectsControlItf::cfUpdateEvent(){ - cfUpdatePeriodAvg.addValue((uint32_t)(HAL_GetTick() - lastCfUpdate)); - lastCfUpdate = HAL_GetTick(); + cfUpdatePeriodAvg.addValue((uint32_t)(micros() - lastCfUpdate)); + lastCfUpdate = micros(); } void EffectsControlItf::fxUpdateEvent(){ - fxPeriodAvg.addValue((uint32_t)(HAL_GetTick() - lastFxUpdate)); - lastFxUpdate = HAL_GetTick(); + fxPeriodAvg.addValue((uint32_t)(micros() - lastFxUpdate)); + lastFxUpdate = micros(); } diff --git a/Firmware/FFBoard/Src/ErrorHandler.cpp b/Firmware/FFBoard/Src/ErrorHandler.cpp index 94f6eaf22..dc7ff60e4 100644 --- a/Firmware/FFBoard/Src/ErrorHandler.cpp +++ b/Firmware/FFBoard/Src/ErrorHandler.cpp @@ -10,6 +10,7 @@ #include "FFBoardMain.h" #include "cppmain.h" #include "critical.hpp" +#include #include std::vector ErrorHandler::errorHandlers; diff --git a/Firmware/FFBoard/Src/Filters.cpp b/Firmware/FFBoard/Src/Filters.cpp index a62074783..0d3adc9c3 100644 --- a/Firmware/FFBoard/Src/Filters.cpp +++ b/Firmware/FFBoard/Src/Filters.cpp @@ -2,18 +2,33 @@ * Filters.cpp * * Created on: Feb 13, 2020 - * Author: Yannick + * Author: Yannick, Vincent + * + * Based on http://www.earlevel.com/main/2012/11/26/biquad-c-source-code/ */ #include "Filters.h" - #include +#ifdef USE_DSP_FUNCTIONS +#include "arm_math.h" +#endif Biquad::Biquad(){ - z1 = z2 = 0.0; +#ifdef USE_DSP_FUNCTIONS + // Clear state + memset(pState, 0, sizeof(pState)); + // Initialize the CMSIS-DSP biquad instance + arm_biquad_cascade_df1_init_f32(&S, 1, pCoeffs, pState); +#else + z1 = 0.0f; + z2 = 0.0f; +#endif } Biquad::Biquad(BiquadType type, float Fc, float Q, float peakGainDB) { +#ifdef USE_DSP_FUNCTIONS + arm_biquad_cascade_df1_init_f32(&S, 1, pCoeffs, pState); +#endif setBiquad(type, Fc, Q, peakGainDB); } @@ -47,13 +62,23 @@ float Biquad::getQ() const { return this->Q; } +void Biquad::setPeakGain(float peakGainDB) { + this->peakGain = peakGainDB; + calcBiquad(); +} + /** * Calculates one step of the filter and returns the output */ float Biquad::process(float in) { - float out = in * a0 + z1; + float out; +#ifdef USE_DSP_FUNCTIONS + arm_biquad_cascade_df1_f32(&S, &in, &out, 1); +#else + out = in * a0 + z1; z1 = in * a1 + z2 - b1 * out; z2 = in * a2 - b2 * out; +#endif return out; } @@ -70,11 +95,18 @@ void Biquad::setBiquad(BiquadType type, float Fc, float Q, float peakGainDB) { * Updates parameters and resets the biquad filter */ void Biquad::calcBiquad(void) { + float norm; + float K, V; +#ifdef USE_DSP_FUNCTIONS + float a0, a1, a2, b1, b2; + V = powf(10, fabsf(peakGain) / 20.0f); + K = arm_sin_f32(PI * Fc) / arm_cos_f32(PI * Fc); +#else z1 = 0.0; z2 = 0.0; - float norm; - float V = pow(10, fabs(peakGain) / 20.0); - float K = tan(M_PI * Fc); + V = pow(10, fabs(peakGain) / 20.0); + K = tan(M_PI * Fc); +#endif switch (this->type) { case BiquadType::lowpass: norm = 1 / (1 + K / Q + K * K); @@ -132,41 +164,84 @@ void Biquad::calcBiquad(void) { break; case BiquadType::lowshelf: if (peakGain >= 0) { // boost - norm = 1 / (1 + sqrt(2) * K + K * K); - a0 = (1 + sqrt(2*V) * K + V * K * K) * norm; + float sqrt2, sqrt2V; +#ifdef USE_DSP_FUNCTIONS + arm_sqrt_f32(2, &sqrt2); + arm_sqrt_f32(2*V, &sqrt2V); +#else + sqrt2 = sqrt(2); + sqrt2V = sqrt(2*V); +#endif + norm = 1 / (1 + sqrt2 * K + K * K); + a0 = (1 + sqrt2V * K + V * K * K) * norm; a1 = 2 * (V * K * K - 1) * norm; - a2 = (1 - sqrt(2*V) * K + V * K * K) * norm; + a2 = (1 - sqrt2V * K + V * K * K) * norm; b1 = 2 * (K * K - 1) * norm; - b2 = (1 - sqrt(2) * K + K * K) * norm; + b2 = (1 - sqrt2 * K + K * K) * norm; } else { // cut - norm = 1 / (1 + sqrt(2*V) * K + V * K * K); - a0 = (1 + sqrt(2) * K + K * K) * norm; + float sqrt2, sqrt2V; +#ifdef USE_DSP_FUNCTIONS + arm_sqrt_f32(2, &sqrt2); + arm_sqrt_f32(2*V, &sqrt2V); +#else + sqrt2 = sqrt(2); + sqrt2V = sqrt(2*V); +#endif + norm = 1 / (1 + sqrt2V * K + V * K * K); + a0 = (1 + sqrt2 * K + K * K) * norm; a1 = 2 * (K * K - 1) * norm; - a2 = (1 - sqrt(2) * K + K * K) * norm; + a2 = (1 - sqrt2 * K + K * K) * norm; b1 = 2 * (V * K * K - 1) * norm; - b2 = (1 - sqrt(2*V) * K + V * K * K) * norm; + b2 = (1 - sqrt2V * K + V * K * K) * norm; } break; case BiquadType::highshelf: if (peakGain >= 0) { // boost - norm = 1 / (1 + sqrt(2) * K + K * K); - a0 = (V + sqrt(2*V) * K + K * K) * norm; + float sqrt2, sqrt2V; +#ifdef USE_DSP_FUNCTIONS + arm_sqrt_f32(2, &sqrt2); + arm_sqrt_f32(2*V, &sqrt2V); +#else + sqrt2 = sqrt(2); + sqrt2V = sqrt(2*V); +#endif + norm = 1 / (1 + sqrt2 * K + K * K); + a0 = (V + sqrt2V * K + K * K) * norm; a1 = 2 * (K * K - V) * norm; - a2 = (V - sqrt(2*V) * K + K * K) * norm; + a2 = (V - sqrt2V * K + K * K) * norm; b1 = 2 * (K * K - 1) * norm; - b2 = (1 - sqrt(2) * K + K * K) * norm; + b2 = (1 - sqrt2 * K + K * K) * norm; } else { // cut - norm = 1 / (V + sqrt(2*V) * K + K * K); - a0 = (1 + sqrt(2) * K + K * K) * norm; + float sqrt2, sqrt2V; +#ifdef USE_DSP_FUNCTIONS + arm_sqrt_f32(2, &sqrt2); + arm_sqrt_f32(2*V, &sqrt2V); +#else + sqrt2 = sqrt(2); + sqrt2V = sqrt(2*V); +#endif + norm = 1 / (V + sqrt2V * K + K * K); + a0 = (1 + sqrt2 * K + K * K) * norm; a1 = 2 * (K * K - 1) * norm; - a2 = (1 - sqrt(2) * K + K * K) * norm; + a2 = (1 - sqrt2 * K + K * K) * norm; b1 = 2 * (K * K - V) * norm; - b2 = (V - sqrt(2*V) * K + K * K) * norm; + b2 = (V - sqrt2V * K + K * K) * norm; } break; } - return; +#ifdef USE_DSP_FUNCTIONS + // Store coefficients in the format required by CMSIS-DSP: {b0, b1, b2, -a1, -a2} + // Note the negated feedback coefficients a1 and a2. + pCoeffs[0] = a0; + pCoeffs[1] = a1; + pCoeffs[2] = a2; + pCoeffs[3] = -b1; + pCoeffs[4] = -b2; + + // Reset state + memset(pState, 0, sizeof(pState)); +#endif } diff --git a/Firmware/FFBoard/Src/HidCommandInterface.cpp b/Firmware/FFBoard/Src/HidCommandInterface.cpp index 9a73a4268..418c3a032 100644 --- a/Firmware/FFBoard/Src/HidCommandInterface.cpp +++ b/Firmware/FFBoard/Src/HidCommandInterface.cpp @@ -99,7 +99,7 @@ void HID_CommandInterface::sendReplies(const std::vector& results } - for(const CommandReply reply : replies){ + for(const CommandReply& reply : replies){ if(reply.type == CommandReplyType::STRING){ continue; // Ignore string only replies } diff --git a/Firmware/FFBoard/Src/HidFFB.cpp b/Firmware/FFBoard/Src/HidFFB.cpp index 21835fef3..fc4f3d3b3 100644 --- a/Firmware/FFBoard/Src/HidFFB.cpp +++ b/Firmware/FFBoard/Src/HidFFB.cpp @@ -12,6 +12,10 @@ #include "cppmain.h" #include +#ifdef USE_DSP_FUNCTIONS +#include "arm_math.h" +#endif + HidFFB::HidFFB(std::shared_ptr ec,uint8_t axisCount) : effects_calc(ec), effects(ec->effects),axisCount(axisCount) { directionEnableMask = 1 << axisCount; // Direction enable bit is last bit after axis enable bits @@ -39,6 +43,10 @@ void HidFFB::setDirectionEnableMask(uint8_t mask){ this->directionEnableMask = mask; } +void HidFFB::updateSamplerate(float newSamplerate){ + effects_calc->updateSamplerate(newSamplerate); +} + bool HidFFB::getFfbActive(){ return this->ffb_active; @@ -231,7 +239,8 @@ void HidFFB::set_constant_effect(FFB_SetConstantForce_Data_t* data){ cfUpdateEvent(); FFB_Effect& effect_p = effects[data->effectBlockIndex-1]; - effect_p.magnitude = data->magnitude; + //effect_p.magnitude = data->magnitude; + effects_calc->pushReconFilterValue(&effect_p, (float)data->magnitude, 0.0f, false); // if(effect_p.state == 0){ // effect_p.state = 1; // Force start effect // } @@ -311,10 +320,16 @@ void HidFFB::set_effect(FFB_SetEffect_t* effect){ if(!overridesCondition){ - float phaseX = M_PI*2.0 * (effect->directionX/36000.0f); +#ifdef USE_DSP_FUNCTIONS + float phaseX = PI*2.0f * (effect->directionX/36000.0f); + effect_p->axisMagnitudes[0] = directionEnable ? arm_sin_f32(phaseX) : (effect->enableAxis & X_AXIS_ENABLE ? (effect->directionX - 18000.0f) / 18000.0f : 0); // Angular vector if dirEnable used otherwise linear or 0 if axis enabled + effect_p->axisMagnitudes[1] = directionEnable ? -arm_cos_f32(phaseX) : (effect->enableAxis & Y_AXIS_ENABLE ? -(effect->directionY - 18000.0f) / 18000.0f : 0); +#else + float phaseX = M_PI*2.0f * (effect->directionX/36000.0); effect_p->axisMagnitudes[0] = directionEnable ? sin(phaseX) : (effect->enableAxis & X_AXIS_ENABLE ? (effect->directionX - 18000.0f) / 18000.0f : 0); // Angular vector if dirEnable used otherwise linear or 0 if axis enabled effect_p->axisMagnitudes[1] = directionEnable ? -cos(phaseX) : (effect->enableAxis & Y_AXIS_ENABLE ? -(effect->directionY - 18000.0f) / 18000.0f : 0); +#endif } #if MAX_AXIS == 3 @@ -449,9 +464,11 @@ void HidFFB::set_periodic(FFB_SetPeriodic_Data_t* report){ FFB_Effect* effect = &effects[report->effectBlockIndex-1]; effect->period = clip(report->period,1,0x7fff); // Period is never 0 - effect->magnitude = report->magnitude; - effect->offset = report->offset; effect->phase = report->phase; + + effects_calc->pushReconFilterValue(effect, (float)report->magnitude, (float)report->offset, true); + //effect->magnitude = report->magnitude; + //effect->offset = report->offset; //effect->counter = 0; } diff --git a/Firmware/FFBoard/Src/I2C.cpp b/Firmware/FFBoard/Src/I2C.cpp index decbe4192..33470ab8a 100644 --- a/Firmware/FFBoard/Src/I2C.cpp +++ b/Firmware/FFBoard/Src/I2C.cpp @@ -14,24 +14,6 @@ ClassIdentifier I2CPort::info = { -//static bool operator==(const I2C_InitTypeDef& lhs, const I2C_InitTypeDef& rhs) { -// return lhs.AddressingMode == rhs.AddressingMode -// && lhs.ClockSpeed == rhs.ClockSpeed -// && lhs.DualAddressMode == rhs.DualAddressMode -// && lhs.DutyCycle == rhs.DutyCycle -// && lhs.GeneralCallMode == rhs.GeneralCallMode -// && lhs.NoStretchMode == rhs.NoStretchMode -// && lhs.OwnAddress1 == rhs.OwnAddress1 -// && lhs.OwnAddress2 == rhs.OwnAddress2; -//} - -//static bool operator==(const I2C_InitTypeDef& lhs, const I2C_InitTypeDef& rhs) { -// return memcmp(&lhs,&rhs,sizeof(I2C_InitTypeDef)) == 0; -//} -// - - - I2CPort::I2CPort(I2C_HandleTypeDef &hi2c,const I2CPortHardwareConfig& presets,uint8_t instance) : CommandHandler("i2c", CLSID_I2CPORT, instance), hi2c(hi2c),presets(presets) { restoreFlashDelayed(); #ifdef I2C_COMMANDS_DISABLED_IF_NOT_USED diff --git a/Firmware/FFBoard/Src/MotorDriver.cpp b/Firmware/FFBoard/Src/MotorDriver.cpp index b7325de9d..cd27754cc 100644 --- a/Firmware/FFBoard/Src/MotorDriver.cpp +++ b/Firmware/FFBoard/Src/MotorDriver.cpp @@ -81,6 +81,12 @@ const ClassIdentifier MotorDriver::getInfo(){ return info; } +/** + * Setup driver when is selected + */ +void MotorDriver::setupDriver(){ + +} /** * Turn the motor with positive/negative power. diff --git a/Firmware/FFBoard/Src/SPI.cpp b/Firmware/FFBoard/Src/SPI.cpp index 37185ea27..937cae4a8 100644 --- a/Firmware/FFBoard/Src/SPI.cpp +++ b/Firmware/FFBoard/Src/SPI.cpp @@ -288,7 +288,7 @@ void SPIPort::SpiError(SPI_HandleTypeDef *hspi) { * Calculates the closest possible clock achievable with the current base clock and prescalers * Returns a pair of {prescaler,actual_clock} */ -std::pair SPIPort::getClosestPrescaler(float clock){ +std::pair SPIPort::getClosestPrescaler(float clock,float min,float max){ std::vector> distances; #if defined(SPI_BAUDRATEPRESCALER_2) distances.push_back({SPI_BAUDRATEPRESCALER_2,(baseclk/2.0)}); @@ -318,7 +318,7 @@ std::pair SPIPort::getClosestPrescaler(float clock){ std::pair bestVal = distances[0]; float bestDist = INFINITY; for(auto& val : distances){ - if(std::abs(clock-val.second) < bestDist){ + if(std::abs(clock-val.second) < bestDist && (val.second > min && val.second < max)){ bestDist = abs(clock-val.second); bestVal = val; } @@ -328,9 +328,11 @@ std::pair SPIPort::getClosestPrescaler(float clock){ SPIDevice::SPIDevice(SPIPort& port,SPIConfig& spiConfig) : spiPort{port},spiConfig{spiConfig}{ spiPort.reserveCsPin(spiConfig.cs); + this->spiConfig.peripheral = port.getPortHandle()->Init; } SPIDevice::SPIDevice(SPIPort& port,OutputPin csPin) : spiPort{port},spiConfig{csPin}{ this->spiConfig.cs = csPin; + this->spiConfig.peripheral = port.getPortHandle()->Init; spiPort.reserveCsPin(spiConfig.cs); } SPIDevice::~SPIDevice() { diff --git a/Firmware/FFBoard/Src/SerialFFB.cpp b/Firmware/FFBoard/Src/SerialFFB.cpp index a439850d4..6e00d25d0 100644 --- a/Firmware/FFBoard/Src/SerialFFB.cpp +++ b/Firmware/FFBoard/Src/SerialFFB.cpp @@ -121,6 +121,10 @@ void SerialFFB::setEffectState(uint8_t id, bool state){ effects[id].state = state ? 1 : 0; } +void SerialFFB::updateSamplerate(float newSamplerate){ + effects_calc->updateSamplerate(newSamplerate); +} + CommandStatus SerialFFB::command(const ParsedCommand& cmd,std::vector& replies){ CommandStatus status = CommandStatus::OK; EffectsControlItf::fxUpdateEvent(); diff --git a/Firmware/FFBoard/Src/SystemCommands.cpp b/Firmware/FFBoard/Src/SystemCommands.cpp index c42b0918a..853f46ec6 100644 --- a/Firmware/FFBoard/Src/SystemCommands.cpp +++ b/Firmware/FFBoard/Src/SystemCommands.cpp @@ -61,7 +61,7 @@ void SystemCommands::registerCommands(){ CommandHandler::registerCommand("errors", FFBoardMain_commands::errors, "Read error states",CMDFLAG_GET); CommandHandler::registerCommand("errorsclr", FFBoardMain_commands::errorsclr, "Reset errors",CMDFLAG_GET); CommandHandler::registerCommand("heapfree", FFBoardMain_commands::heapfree, "Memory info",CMDFLAG_GET); -#if configUSE_STATS_FORMATTING_FUNCTIONS> 0 +#if ( ( configGENERATE_RUN_TIME_STATS == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) CommandHandler::registerCommand("taskstats", FFBoardMain_commands::taskstats, "Task stats",CMDFLAG_GET); #endif CommandHandler::registerCommand("format", FFBoardMain_commands::format, "set format=1 to erase all stored values",CMDFLAG_SET); @@ -77,6 +77,9 @@ void SystemCommands::registerCommands(){ #if defined(SIGNATURE) CommandHandler::registerCommand("signature", FFBoardMain_commands::signature, "Chip signature in OTP. setadr to write data. set=1 to lock",CMDFLAG_GETADR | CMDFLAG_SETADR | CMDFLAG_GET | CMDFLAG_INFOSTRING); #endif +#if ( ( configUSE_TRACE_FACILITY == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + CommandHandler::registerCommand("tasklist", FFBoardMain_commands::tasklist, "Task list",CMDFLAG_GET); +#endif } // Choose lower optimize level because the compiler likes to blow up this function @@ -218,7 +221,7 @@ CommandStatus SystemCommands::internalCommand(const ParsedCommand& cmd,std::vect } - case FFBoardMain_commands::mallinfo: // UNUSED since freertos + case FFBoardMain_commands::mallinfo: { CommandReply reply; struct mallinfo info = mallinfo(); @@ -238,14 +241,23 @@ CommandStatus SystemCommands::internalCommand(const ParsedCommand& cmd,std::vect replies.emplace_back(xPortGetFreeHeapSize(),xPortGetMinimumEverFreeHeapSize()); break; } -#if configUSE_STATS_FORMATTING_FUNCTIONS>0 +#if ( ( configGENERATE_RUN_TIME_STATS == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) case FFBoardMain_commands::taskstats: { - char repl[800]; + char repl[uxTaskGetNumberOfTasks()*64]; vTaskGetRunTimeStats(repl); replies.emplace_back("\n"+std::string(repl)); break; } +#endif +#if ( ( configUSE_TRACE_FACILITY == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + case FFBoardMain_commands::tasklist: + { + char repl[uxTaskGetNumberOfTasks()*64]; + vTaskList(repl); + replies.emplace_back("\n"+std::string(repl)); + break; + } #endif case FFBoardMain_commands::lsactive: { @@ -267,6 +279,7 @@ CommandStatus SystemCommands::internalCommand(const ParsedCommand& cmd,std::vect if(cmd.type == CMDtype::set && cmd.val==1){ if(Flash_Format()){ + Flash_Write_Defaults(); // Restore default values if present flag = CommandStatus::OK; }else{ flag = CommandStatus::ERR; diff --git a/Firmware/FFBoard/Src/cppmain.cpp b/Firmware/FFBoard/Src/cppmain.cpp index aa0f9a76d..412b75efb 100644 --- a/Firmware/FFBoard/Src/cppmain.cpp +++ b/Firmware/FFBoard/Src/cppmain.cpp @@ -15,6 +15,7 @@ extern IWDG_HandleTypeDef hiwdg; // Watchdog bool running = true; bool mainclassChosen = false; +volatile bool forceErase = false; uint16_t main_id = 0; @@ -46,6 +47,11 @@ void cppmain() { Error_Handler(); } + if(forceErase){ + Flash_Format(); + Flash_Write_Defaults(); + } + // // Check if flash is initialized // uint16_t lastVersion = 0; // if(!Flash_Read(ADR_SW_VERSION, &lastVersion)){ // Version never written @@ -59,11 +65,13 @@ void cppmain() { // Check if flash is initialized uint16_t lastFlashVersion = 0; if(!Flash_Read(ADR_FLASH_VERSION, &lastFlashVersion)){ // Version never written + Flash_Write_Defaults(); Flash_Write(ADR_FLASH_VERSION, FLASH_VERSION); } Flash_Read(ADR_FLASH_VERSION,&lastFlashVersion); if(lastFlashVersion != FLASH_VERSION){ Flash_Format(); // Major version changed or could not write initial value. force a format + Flash_Write_Defaults(); Flash_Write(ADR_FLASH_VERSION, FLASH_VERSION); } diff --git a/Firmware/FFBoard/Src/flash_helpers.cpp b/Firmware/FFBoard/Src/flash_helpers.cpp index cc8256ec0..75e0f61e0 100644 --- a/Firmware/FFBoard/Src/flash_helpers.cpp +++ b/Firmware/FFBoard/Src/flash_helpers.cpp @@ -8,6 +8,7 @@ #include "eeprom_addresses.h" #include #include "mutex.hpp" +#include cpp_freertos::MutexStandard flashMutex; // Flash helpers @@ -107,7 +108,10 @@ bool Flash_ReadWriteDefault(uint16_t adr,uint16_t *buf,uint16_t def){ uint8_t i2cBufferEeprom[sizeof(uint16_t)] = {0}; #include "string.h" // Memcpy #include "cassert" - +#include +#include "I2C.h" +I2CDevice i2cdeveeprom; +extern I2CPort i2cport_int; bool Flash_Write(uint16_t adr,uint16_t dat){ uint16_t dataLength = sizeof(dat); @@ -120,12 +124,14 @@ bool Flash_Write(uint16_t adr,uint16_t dat){ // Do segmented writes bool res = false; while(curAdr < adr+dataLength){ - while(!HAL_I2C_IsDeviceReady(&I2C_PORT_EEPROM, I2C_EEPROM_ADR, 100, I2C_EEPROM_TIMEOUT) == HAL_OK){ - HAL_Delay(1); +// i2cport_int.isDeviceReady(i2cdeveeprom, I2C_EEPROM_ADR, 100, I2C_EEPROM_TIMEOUT,false) + while(!i2cport_int.isDeviceReady(&i2cdeveeprom, I2C_EEPROM_ADR, 100, I2C_EEPROM_TIMEOUT,false)){ + vTaskDelay(1); } uint16_t wLen = std::min(dataLength,I2C_EEPROM_PAGEWRITE_SIZE - (adr % I2C_EEPROM_PAGEWRITE_SIZE)); - res = HAL_I2C_Mem_Write(&I2C_PORT_EEPROM, I2C_EEPROM_ADR, curAdr, I2C_EEPROM_ADR_SIZE, i2cBufferEeprom, wLen,I2C_EEPROM_TIMEOUT) == HAL_OK; + res = i2cport_int.writeMem(&i2cdeveeprom, I2C_EEPROM_ADR, curAdr, I2C_EEPROM_ADR_SIZE, i2cBufferEeprom, wLen, I2C_EEPROM_TIMEOUT, false); + //res = HAL_I2C_Mem_Write(&I2C_PORT_EEPROM, I2C_EEPROM_ADR, curAdr, I2C_EEPROM_ADR_SIZE, i2cBufferEeprom, wLen,I2C_EEPROM_TIMEOUT) == HAL_OK; curAdr+=wLen; if(!res){ break; @@ -146,10 +152,12 @@ bool Flash_ReadWriteDefault(uint16_t adr,uint16_t *buf,uint16_t def){ bool Flash_Read(uint16_t adr,uint16_t *buf, bool checkempty){ adr *= sizeof(*buf)/I2C_EEPROM_DATA_SIZE; assert(adr < I2C_EEPROM_SIZE); - while(!HAL_I2C_IsDeviceReady(&I2C_PORT_EEPROM, I2C_EEPROM_ADR, 100, I2C_EEPROM_TIMEOUT) == HAL_OK){ - HAL_Delay(1); + while(!i2cport_int.isDeviceReady(&i2cdeveeprom, I2C_EEPROM_ADR, 100, I2C_EEPROM_TIMEOUT,false)){ + vTaskDelay(1); } - bool res = HAL_I2C_Mem_Read(&I2C_PORT_EEPROM, I2C_EEPROM_ADR, I2C_EEPROM_OFS+adr, I2C_EEPROM_ADR_SIZE, i2cBufferEeprom, 2, I2C_EEPROM_TIMEOUT) == HAL_OK; + + //bool res = HAL_I2C_Mem_Read(&I2C_PORT_EEPROM, I2C_EEPROM_ADR, I2C_EEPROM_OFS+adr, I2C_EEPROM_ADR_SIZE, i2cBufferEeprom, 2, I2C_EEPROM_TIMEOUT) == HAL_OK; + bool res = i2cport_int.readMem(&i2cdeveeprom, I2C_EEPROM_ADR, I2C_EEPROM_OFS+adr, I2C_EEPROM_ADR_SIZE, i2cBufferEeprom, 2, I2C_EEPROM_TIMEOUT, false); if(checkempty){ bool empty = true; @@ -175,19 +183,20 @@ bool Flash_Format(){ eraseBuf.fill(I2C_EEPROM_ERASED); for(uint32_t i=I2C_EEPROM_OFS;i(I2C_EEPROM_PAGEWRITE_SIZE,I2C_EEPROM_SIZE-i),I2C_EEPROM_TIMEOUT) == HAL_OK; + //bool res = HAL_I2C_Mem_Write(&I2C_PORT_EEPROM, I2C_EEPROM_ADR, I2C_EEPROM_OFS+i, I2C_EEPROM_ADR_SIZE, eraseBuf.data(), std::min(I2C_EEPROM_PAGEWRITE_SIZE,I2C_EEPROM_SIZE-i),I2C_EEPROM_TIMEOUT) == HAL_OK; + bool res = i2cport_int.writeMem(&i2cdeveeprom, I2C_EEPROM_ADR, I2C_EEPROM_OFS+i, I2C_EEPROM_ADR_SIZE, eraseBuf.data(), std::min(I2C_EEPROM_PAGEWRITE_SIZE,I2C_EEPROM_SIZE-i), I2C_EEPROM_TIMEOUT, false); if(!res){ flag = false; }else{ - while(!HAL_I2C_IsDeviceReady(&I2C_PORT_EEPROM, I2C_EEPROM_ADR, 100, I2C_EEPROM_TIMEOUT) == HAL_OK){ - HAL_Delay(1); + while(!i2cport_int.isDeviceReady(&i2cdeveeprom, I2C_EEPROM_ADR, 100, I2C_EEPROM_TIMEOUT,false)){ + vTaskDelay(1); } } } return flag; } bool Flash_Init(){ - return HAL_I2C_IsDeviceReady(&I2C_PORT_EEPROM, I2C_EEPROM_ADR, 10, I2C_EEPROM_TIMEOUT) == HAL_OK; + return i2cport_int.isDeviceReady(&i2cdeveeprom, I2C_EEPROM_ADR, 50, I2C_EEPROM_TIMEOUT,false); } #else @@ -283,3 +292,22 @@ __weak bool OTP_Read(uint16_t adroffset,uint64_t* dat){ } #endif + +#ifndef FLASH_FACTORY_DEFAULTS_OVERRIDE + /** + * To define factory defaults create a span/array in a core folder defined for example as + * const auto flash_defaults = std::to_array>({ {ADR_CURRENT_CONFIG,1} }); // ADR,VALUE pairs + * const std::span> flash_factory_defaults = flash_defaults; + */ +const std::array,0> empty_flash_defaults; // Empty +const std::span> flash_factory_defaults = empty_flash_defaults; +#endif + +/** + * Writes factory default values to flash. Does nothing if no defaults are defined + */ +void Flash_Write_Defaults(){ + for(const std::pair &kv : flash_factory_defaults){ + Flash_Write(kv.first, kv.second); // Try to write values + } +} \ No newline at end of file diff --git a/Firmware/FFBoard/UserExtensions/Inc/FFBHIDMain.h b/Firmware/FFBoard/UserExtensions/Inc/FFBHIDMain.h index 72855f793..736b6c81b 100644 --- a/Firmware/FFBoard/UserExtensions/Inc/FFBHIDMain.h +++ b/Firmware/FFBoard/UserExtensions/Inc/FFBHIDMain.h @@ -33,13 +33,17 @@ #include "SelectableInputs.h" #include "thread.hpp" -class FFBHIDMain: public FFBoardMain, public cpp_freertos::Thread, PersistentStorage,ExtiHandler,public UsbHidHandler, ErrorHandler, SelectableInputs{ +class FFBHIDMain: public FFBoardMain, public cpp_freertos::Thread, PersistentStorage,ExtiHandler,public UsbHidHandler, ErrorHandler, SelectableInputs +#ifdef TIM_FFB +, TimerHandler // Adds timer handler +#endif +{ enum class FFBWheel_commands : uint32_t{ ffbactive,axes,btntypes,lsbtn,addbtn,aintypes,lsain,addain,hidrate,hidsendspd,estop,cfrate }; public: - FFBHIDMain(uint8_t axisCount); + FFBHIDMain(uint8_t axisCount,bool hidAxis32b = false); virtual ~FFBHIDMain(); void setFFBEffectsCalc(std::shared_ptr ffb,std::shared_ptr effects_calc); @@ -74,6 +78,11 @@ class FFBHIDMain: public FFBoardMain, public cpp_freertos::Thread, PersistentSto void errorCallback(const Error &error, bool cleared); void systick(); +#ifdef TIM_FFB + void timerElapsed(TIM_HandleTypeDef* htim); +#endif + + float getCurFFBFreq(); protected: std::shared_ptr ffb; @@ -91,9 +100,33 @@ class FFBHIDMain: public FFBoardMain, public cpp_freertos::Thread, PersistentSto * Warning: Report rate initialized by bInterval is overridden by saved speed preset at startup! */ void setReportRate(uint8_t rateidx); - uint8_t usb_report_rate = HID_BINTERVAL; //1 = 1000hz, 2 = 500hz, 3 = 333hz 4 = 250hz, 5 = 200hz 6 = 166hz, 8 = 125hz etc... - uint8_t usb_report_rate_idx = 0; - const uint8_t usb_report_rates[4] = {1,2,4,8}; // Maps stored hid speed to report rates + uint8_t usb_report_rate = HID_BINTERVAL; //for FS USB 1 = 1000hz, 2 = 500hz, 3 = 333hz 4 = 250hz, 5 = 200hz 6 = 166hz, 8 = 125hz etc... + uint8_t usb_report_rate_idx = ffbrates.defaultmode; +#ifndef TIM_FFB + uint8_t ffb_rate_divider = 0; + uint8_t ffb_rate_counter = 0; +#endif + + + struct FFB_update_rates{ + struct FFB_update_rate_divider{ + uint8_t basediv; + uint8_t hiddiv; + }; + +#if TUD_OPT_HIGH_SPEED // divider pair + const uint8_t defaultmode = 3; + uint32_t basefreq = 8000; + std::array dividers = {{{1,1},{2,1},{4,1},{8,1},{16,1},{32,1},{64,1}}}; // 8khz to 125hz +#else + const uint8_t defaultmode = 0; + uint32_t basefreq = 1000; + std::array dividers = {{{1,1},{2,1},{4,1},{8,1}}}; // 8 entries max. 1khz to 125hz +#endif + }; + const static FFB_update_rates ffbrates; + + const bool hidAxis32b; std::string usb_report_rates_names(); @@ -105,8 +138,8 @@ class FFBHIDMain: public FFBoardMain, public cpp_freertos::Thread, PersistentSto std::vector> btns; std::vector> analog_inputs; - reportHID_t reportHID; - reportHID_t lastReportHID; + std::unique_ptr reportHID; + uint8_t reportSendCounter = 0; const uint8_t analogAxisCount = 8; diff --git a/Firmware/FFBoard/UserExtensions/Inc/FFBWheel.h b/Firmware/FFBoard/UserExtensions/Inc/FFBWheel.h index 0f7be1be1..274e93cc0 100644 --- a/Firmware/FFBoard/UserExtensions/Inc/FFBWheel.h +++ b/Firmware/FFBoard/UserExtensions/Inc/FFBWheel.h @@ -12,6 +12,12 @@ #include "FFBHIDMain.h" +#ifdef HIDAXISRES_USE_32B_DESC +#define FFBWHEEL_32B_MODE true +#else +#define FFBWHEEL_32B_MODE false +#endif + class FFBWheel : public FFBHIDMain { public: FFBWheel(); diff --git a/Firmware/FFBoard/UserExtensions/Inc/TMC4671.h b/Firmware/FFBoard/UserExtensions/Inc/TMC4671.h index dd19e51fb..2dffac900 100644 --- a/Firmware/FFBoard/UserExtensions/Inc/TMC4671.h +++ b/Firmware/FFBoard/UserExtensions/Inc/TMC4671.h @@ -2,7 +2,7 @@ * TMC4671.h * * Created on: Feb 1, 2020 - * Author: Yannick + * Author: Yannick, Vincent */ #ifndef TMC4671_H_ @@ -21,7 +21,7 @@ #include "ExtiHandler.h" #include "SPI.h" #include "TimerHandler.h" - +#include #include "semaphore.hpp" #include #include "cpp_target_config.h" @@ -38,6 +38,26 @@ extern SPI_HandleTypeDef HSPIDRV; extern TIM_HandleTypeDef TIM_TMC; #endif +#ifndef TMC4671_DEFAULT_CURRENT_SCALER +#define TMC4671_DEFAULT_CURRENT_SCALER 0 +#endif +#ifndef TMC4671_DEFAULT_CLOCKFREQ +#define TMC4671_DEFAULT_CLOCKFREQ 25e6 +#endif +#ifndef TMC4671_DEFAULT_BBM +#define TMC4671_DEFAULT_BBM 20 +#endif +#ifndef TMC4671_DEFAULT_ANALOGENC_SKIPCAL +#define TMC4671_DEFAULT_ANALOGENC_SKIPCAL 0 +#endif +#ifndef TMC4671_ITUNE_CUTOFF +#define TMC4671_ITUNE_CUTOFF 0.04 +#endif +#ifndef TIM_TMC_ARR +#define TIM_TMC_ARR 200 +#endif + + enum class TMC_ControlState : uint32_t {uninitialized,waitPower,Shutdown,Running,EncoderInit,EncoderFinished,HardError,OverTemp,IndexSearch,FullCalibration,ExternalEncoderInit,Pidautotune}; enum class TMC_PwmMode : uint8_t {off = 0,HSlow_LShigh = 1, HShigh_LSlow = 2, res2 = 3, res3 = 4, PWM_LS = 5, PWM_HS = 6, PWM_FOC = 7}; @@ -46,7 +66,7 @@ enum class TMC_StartupType{NONE,coldStart,warmStart}; enum class TMC_GpioMode{DebugSpi,DSAdcClkOut,DSAdcClkIn,Aout_Bin,Ain_Bout,Aout_Bout,Ain_Bin}; -enum class MotorType : uint8_t {NONE=0,DC=1,STEPPER=2,BLDC=3,ERR}; +enum class MotorType : uint8_t {NONE=0,DC=1,STEPPER=2,BLDC=3}; enum class PhiE : uint8_t {ext=1,openloop=2,abn=3,hall=5,aenc=6,aencE=7,NONE,extEncoder}; enum class MotionMode : uint8_t {stop=0,torque=1,velocity=2,position=3,prbsflux=4,prbstorque=5,prbsvelocity=6,uqudext=8,encminimove=9,NONE}; enum class FFMode : uint8_t {none=0,velocity=1,torque=2}; @@ -54,18 +74,8 @@ enum class PosSelection : uint8_t {PhiE=0, PhiE_ext=1, PhiE_openloop=2, PhiE_abn enum class VelSelection : uint8_t {PhiE=0, PhiE_ext=1, PhiE_openloop=2, PhiE_abn=3, res1=4, PhiE_hal=5, PhiE_aenc=6, PhiA_aenc=7, res2=8, PhiM_abn=9, PhiM_abn2=10, PhiM_aenc=11, PhiM_hal=12}; enum class EncoderType_TMC : uint8_t {NONE=0,abn=1,sincos=2,uvw=3,hall=4,ext=5}; // max 7 -// Hardware versions for identifying different types. 31 versions valid +//// Hardware versions for identifying different types. 31 versions valid enum class TMC_HW_Ver : uint8_t {NONE=0,v1_0,v1_2,v1_2_2,v1_2_2_LEM20,v1_2_2_100mv,v1_3_66mv}; -// Selectable version names to be listed in commands -const std::vector> tmcHwVersionNames{ - std::make_pair(TMC_HW_Ver::NONE,"Undefined"), // Do not select. Default but disables some safety features - std::make_pair(TMC_HW_Ver::v1_0,"v1.0 AD8417"), - std::make_pair(TMC_HW_Ver::v1_2,"v1.2 AD8417"), - std::make_pair(TMC_HW_Ver::v1_2_2,"v1.2.2 LEM GO 10 (80mV/A)"), - std::make_pair(TMC_HW_Ver::v1_2_2_LEM20,"v1.2.2 LEM GO 20 (40mV/A)"), - std::make_pair(TMC_HW_Ver::v1_2_2_100mv,"v1.2/3 100mV/A"), - std::make_pair(TMC_HW_Ver::v1_3_66mv,"v1.3 ACS724 30A (66mV/A)") -}; struct TMC4671MotConf{ MotorType motor_type = MotorType::NONE; //saved @@ -81,23 +91,70 @@ struct TMC4671MotConf{ * Settings that depend on the hardware version */ struct TMC4671HardwareTypeConf{ - TMC_HW_Ver hwVersion = TMC_HW_Ver::NONE; + const char* name="CUSTOM"; + uint8_t hwVersion = 0; int adcOffset = 0; - float thermistor_R2 = 1500; - float thermistor_R = 22000; - float thermistor_Beta = 4300; - bool temperatureEnabled = false; // Enables temperature readings - float temp_limit = 90; - float currentScaler = 2.5 / (0x7fff * 60.0 * 0.0015); // Converts from adc counts to current in Amps - uint16_t brakeLimLow = 50700; - uint16_t brakeLimHigh = 50900; + + struct ThermistorSettings{ + float thermistor_R2 = 1500; + float thermistor_R = 22000; + float thermistor_Beta = 4300; + float temp_limit = 90; + bool temperatureEnabled = false; // Enables temperature readings + }; + ThermistorSettings thermistorSettings; + + + float currentScaler = TMC4671_DEFAULT_CURRENT_SCALER; // Converts from adc counts to current in Amps + uint16_t brakeLimLow = 0xffff; + uint16_t brakeLimHigh = 0xffff; float vmScaler = (2.5 / 0x7fff) * ((1.5+71.5)/1.5); float vSenseMult = VOLTAGE_MULT_DEFAULT; - float clockfreq = 25e6; - uint8_t bbm = 20; + float clockfreq = TMC4671_DEFAULT_CLOCKFREQ; + uint8_t bbm = TMC4671_DEFAULT_BBM; float fluxDissipationScaler = 0.5; - bool allowFluxDissipationDeactivation = true; - // Todo restrict allowed motor and encoder types + + /** + * Flags which features are enabled in this hardware type + */ + struct SupportedModes_s { + uint32_t mot_none: 1 = 1, + mot_dc : 1 = 1, + mot_bldc: 1 = 1, + mot_stepper:1 = 1, + + enc_none:1 = 1, + enc_abn:1 = 1, + enc_sincos:1 = 1, + enc_uvw:1 = 1, + enc_hall:1 = 1, + enc_ext:1 = 1, + + analog_enc_skip_cal:1 = TMC4671_DEFAULT_ANALOGENC_SKIPCAL, + + allowFluxDissipationDeactivation:1 = 1; + }; + SupportedModes_s flags; + bool isEncSupported(EncoderType_TMC type){ + switch(type){ + case EncoderType_TMC::NONE: return flags.enc_none; + case EncoderType_TMC::abn: return flags.enc_abn; + case EncoderType_TMC::ext: return flags.enc_ext; + case EncoderType_TMC::sincos: return flags.enc_sincos; + case EncoderType_TMC::hall: return flags.enc_hall; + case EncoderType_TMC::uvw: return flags.enc_uvw; + default: return false; + } + } + bool isMotSupported(MotorType type){ + switch(type){ + case MotorType::NONE: return flags.mot_none; + case MotorType::DC: return flags.mot_dc; + case MotorType::STEPPER: return flags.mot_stepper; + case MotorType::BLDC: return flags.mot_bldc; + default: return false; + } + } }; @@ -157,7 +214,6 @@ struct TMC4671MainConfig{ uint16_t adc_I1_offset = 33415; uint16_t adc_I0_scale = 256; uint16_t adc_I1_scale = 256; - bool canChangeHwType = true; // Allows changing the hardware version by commands bool encoderReversed = false; bool combineEncoder = false; bool invertForce = false; @@ -179,7 +235,7 @@ struct TMC4671PIDConf{ struct TMC4671Limits{ uint16_t pid_torque_flux_ddt = 32767; uint16_t pid_uq_ud = 30000; - uint16_t pid_torque_flux = 32767; + uint16_t pid_torque_flux = 30000; uint32_t pid_acc_lim = 2147483647; uint32_t pid_vel_lim = 2147483647; int32_t pid_pos_low = -2147483647; @@ -237,7 +293,7 @@ struct TMC4671AENCConf{ int16_t AENC0_scale = 256; uint16_t AENC1_offset = 0x7fff; int16_t AENC1_scale = 256; - uint16_t AENC2_offset = 20000; + uint16_t AENC2_offset = 0x7fff; int16_t AENC2_scale = 256; int16_t nMask = 0; // 0x3c & 0xffff0000 @@ -289,6 +345,17 @@ class TMC4671Biquad{ } TMC4671Biquad(const TMC4671Biquad_t bq) : params(bq){} TMC4671Biquad(const Biquad& bq,bool enable = true){ +#ifdef USE_DSP_FUNCTIONS + const float* coeffs = bq.getCoeffs(); + // coeffs is in order {b0, b1, b2, -a1, -a2} + // TMC expects {b0, b1, b2, a1, a2} with a1 and a2 negated + this->params.b0 = (int32_t)(coeffs[0] * (float)(1 << 29)); + this->params.b1 = (int32_t)(coeffs[1] * (float)(1 << 29)); + this->params.b2 = (int32_t)(coeffs[2] * (float)(1 << 29)); + this->params.a1 = (int32_t)(coeffs[3] * (float)(1 << 29)); + this->params.a2 = (int32_t)(coeffs[4] * (float)(1 << 29)); + this->params.enable = bq.getFc() > 0 ? enable : false; +#else // Note: trinamic swapped the naming of b and a from the regular convention in the datasheet and a and b are possibly inverse to b in our filter class this->params.a1 = -(int32_t)(bq.b1 * (float)(1 << 29)); this->params.a2 = -(int32_t)(bq.b2 * (float)(1 << 29)); @@ -296,6 +363,7 @@ class TMC4671Biquad{ this->params.b1 = (int32_t)(bq.a1 * (float)(1 << 29)); this->params.b2 = (int32_t)(bq.a2 * (float)(1 << 29)); this->params.enable = bq.getFc() > 0 ? enable : false; +#endif } void enable(bool enable){ params.enable = enable; @@ -346,7 +414,7 @@ friend class TMCDebugBridge; TMC4671(SPIPort& spiport,OutputPin cspin,uint8_t address=1); - void setHwType(TMC_HW_Ver type); + void setHwType(uint8_t type); void setAddress(uint8_t address); @@ -356,6 +424,7 @@ friend class TMCDebugBridge; TMC4671MainConfig conf; + void setupDriver(); bool initialize(); void initializeWithPower(); @@ -429,15 +498,20 @@ friend class TMCDebugBridge; void stopMotor(); void startMotor(); + void setPowerLimit(uint16_t power) override; + void emergencyStop(bool reset); bool emergency = false; bool estopTriggered = false; void turn(int16_t power); + + int16_t getVelocityControllerTorque(); int16_t nextFlux = 0; int16_t idleFlux = 0; uint16_t maxOffsetFlux = 0; int16_t bangInitPower = 5000; // Default current in setup routines + uint16_t maxPowerAxis = 0; int16_t controlFluxDissipate(); const float fluxDissipationLimit = 1000; @@ -570,7 +644,10 @@ friend class TMCDebugBridge; TMC4671* tmc; }; + static std::span tmc4671_hw_configs; // Can override in external target file + private: + uint8_t drv_address = 0; OutputPin enablePin = OutputPin(*DRV_ENABLE_GPIO_Port,DRV_ENABLE_Pin); const Error indexNotHitError = Error(ErrorCode::encoderIndexMissed,ErrorType::critical,"Encoder index missed"); const Error lowVoltageError = Error(ErrorCode::undervoltage,ErrorType::warning,"Low motor voltage"); @@ -600,6 +677,7 @@ friend class TMCDebugBridge; bool fullCalibrationInProgress = false; bool phiErestored = false; bool encHallRestored = false; + bool canChangeHwType = true; // Allows changing the hardware version by commands //int32_t phiEOffsetRestored = 0; //-0x8000 to 0x7fff uint8_t calibrationFailCount = 2; @@ -635,6 +713,8 @@ friend class TMCDebugBridge; void errorCallback(const Error &error, bool cleared); bool pidAutoTune(); + void replyHardwareVersions(const std::span& versions,std::vector& replies); + uint32_t initTime = 0; bool manualEncAlign = false; bool spiActive = false; // Flag for tx interrupt that the transfer was started by this instance @@ -676,5 +756,3 @@ class TMC_2 : public TMC4671 { }; #endif #endif /* TMC4671_H_ */ - - diff --git a/Firmware/FFBoard/UserExtensions/Inc/eeprom_addresses.h b/Firmware/FFBoard/UserExtensions/Inc/eeprom_addresses.h index d05638476..bed80e3af 100644 --- a/Firmware/FFBoard/UserExtensions/Inc/eeprom_addresses.h +++ b/Firmware/FFBoard/UserExtensions/Inc/eeprom_addresses.h @@ -13,11 +13,11 @@ #include "main.h" // Change this to the amount of currently registered variables -#define NB_OF_VAR 164 +#define NB_OF_VAR 168 extern const uint16_t VirtAddVarTab[NB_OF_VAR]; // Amount of variables in exportable list -#define NB_EXPORTABLE_ADR 149 +#define NB_EXPORTABLE_ADR 153 extern const uint16_t exportableFlashAddresses[NB_EXPORTABLE_ADR]; @@ -88,6 +88,7 @@ uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data) will return 1 if #define ADR_FFB_EFFECTS1 0x284 // 0-7 inertia, 8-15 friction #define ADR_FFB_EFFECTS2 0x285 // 0-7 spring, 8-15 damper #define ADR_FFB_EFFECTS3 0x286 // 0-7 friction ramp up zone, 8-9 filterProfile +#define ADR_FFB_RECONSTRUCTION_FILTER 0x287 // 0-1 recon filter mode // Button Sources: #define ADR_ADS111X_CONF1 0x290 // How many axis configured 1-3 @@ -98,6 +99,7 @@ uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data) will return 1 if #define ADR_AXIS1_DEGREES 0x303 #define ADR_AXIS1_MAX_SPEED 0x304 // Store the max speed #define ADR_AXIS1_MAX_ACCEL 0x305 // Store the max accel +#define ADR_AXIS1_MAX_SLEWRATE_DRV 0x306 // Max slew rate for drv #define ADR_AXIS1_ENDSTOP 0x307 // 0-7 endstop margin, 8-15 endstop stiffness #define ADR_AXIS1_EFFECTS1 0x308 // 0-7 idlespring, 8-15 damper #define ADR_AXIS1_SPEEDACCEL_FILTER 0x309 // Speed/Accel filter Lowpass profile @@ -124,6 +126,7 @@ uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data) will return 1 if #define ADR_AXIS2_DEGREES 0x343 #define ADR_AXIS2_MAX_SPEED 0x344 // Store the max speed #define ADR_AXIS2_MAX_ACCEL 0x345 // Store the max accel +#define ADR_AXIS2_MAX_SLEWRATE_DRV 0x346 // Max slew rate for drv #define ADR_AXIS2_ENDSTOP 0x347 // 0-7 endstop margin, 8-15 endstop stiffness #define ADR_AXIS2_EFFECTS1 0x348 // 0-7 idlespring, 8-15 damper #define ADR_AXIS2_SPEEDACCEL_FILTER 0x349 // Speed/Accel filter Lowpass profile @@ -150,6 +153,7 @@ uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data) will return 1 if #define ADR_AXIS3_DEGREES 0x383 #define ADR_AXIS3_MAX_SPEED 0x384 // Store the max speed #define ADR_AXIS3_MAX_ACCEL 0x385 // Store the max accel +#define ADR_AXIS3_MAX_SLEWRATE_DRV 0x386 // Max slew rate for drv #define ADR_AXIS3_ENDSTOP 0x387 // 0-7 endstop margin, 8-15 endstop stiffness #define ADR_AXIS3_EFFECTS1 0x388 // 0-7 idlespring, 8-15 damper #define ADR_AXIS3_SPEEDACCEL_FILTER 0x389 // Speed/Accel filter Lowpass profile diff --git a/Firmware/FFBoard/UserExtensions/Inc/usb_descriptors.h b/Firmware/FFBoard/UserExtensions/Inc/usb_descriptors.h index b4d6d8ee8..ef8507300 100644 --- a/Firmware/FFBoard/UserExtensions/Inc/usb_descriptors.h +++ b/Firmware/FFBoard/UserExtensions/Inc/usb_descriptors.h @@ -24,6 +24,16 @@ typedef struct usb_string_desc const std::vector interfaces; } usb_string_desc_t; +/* + * Base combined usb config descriptor for HID and CDC composite device + */ +#define USB_CONF_DESC_HID_CDC(HIDREPSIZE,EPSIZE) \ + /* Config number, interface count, string index, total length, attribute, power in mA*/\ + TUD_CONFIG_DESCRIPTOR(1, 3, 0, (TUD_CONFIG_DESC_LEN + TUD_CDC_DESC_LEN + TUD_HID_INOUT_DESC_LEN), TUSB_DESC_CONFIG_ATT_REMOTE_WAKEUP | TUSB_DESC_CONFIG_ATT_SELF_POWERED, 100),\ + /* 1st CDC: Interface number, string index, EP notification address and size, EP data address (out, in) and size.*/\ + TUD_CDC_DESCRIPTOR(0, 4, 0x82, 8, 0x01, 0x81, EPSIZE),\ + /* HID Descriptor. EP 83 and 2*/\ + TUD_HID_INOUT_DESCRIPTOR(2, 5, HID_ITF_PROTOCOL_NONE, HIDREPSIZE, 0x83, 0x02,EPSIZE, HID_BINTERVAL) /* * Device descriptors @@ -42,7 +52,9 @@ extern const uint8_t usb_cdc_hid_conf_1axis[]; #ifdef AXIS2_FFB_HID_DESC extern const uint8_t usb_cdc_hid_conf_2axis[]; #endif - +#ifdef AXIS2_FFB_HID_DESC_32B +extern const uint8_t usb_cdc_hid_conf_2axis_32b[]; +#endif #ifdef FFB_HID_DESC_GAMEPAD extern const uint8_t usb_cdc_hid_conf_gamepad[]; #endif diff --git a/Firmware/FFBoard/UserExtensions/Inc/usb_hid_ffb_desc.h b/Firmware/FFBoard/UserExtensions/Inc/usb_hid_ffb_desc.h index d6067effe..242536eba 100644 --- a/Firmware/FFBoard/UserExtensions/Inc/usb_hid_ffb_desc.h +++ b/Firmware/FFBoard/UserExtensions/Inc/usb_hid_ffb_desc.h @@ -8,21 +8,769 @@ #ifndef USB_INC_USB_HID_FFB_DESC_H_ #define USB_INC_USB_HID_FFB_DESC_H_ #include "constants.h" +#include "hid.h" +/** \defgroup HID Descriptors + * \details Contains definitions of different HID descriptor parts * + * @{ + */ -#define USB_HID_1FFB_REPORT_DESC_SIZE 1196 -#ifdef AXIS1_FFB_HID_DESC -extern const uint8_t hid_1ffb_desc[USB_HID_1FFB_REPORT_DESC_SIZE]; +#if defined(HIDAXISRES_32B_BITS) && HIDAXISRES_32B_BITS > 2 && HIDAXISRES_32B_BITS < 32 +// 7FFFFFFF for 32 +#define HIDAXISRES_32B_MAXS (1 << (HIDAXISRES_32B_BITS-1))-1 +#else +#define HIDAXISRES_32B_MAXS 0x7FFFFFFF +#define HIDAXISRES_32B_BITS 32 +#endif + +// HID descriptor building blocks +#define HIDDESC_32B_ENTRY(count) /* LOGICAL_MINIMUM (-7FFFFFFF)*/\ + HID_LOGICAL_MIN_N(-HIDAXISRES_32B_MAXS,3), /*0x17, 0x01, 0x00, 0x00, 0x80,*/\ + /* LOGICAL_MAXIMUM (7FFFFFFF)*/\ + HID_LOGICAL_MAX_N(HIDAXISRES_32B_MAXS,3), /* 0x27, 0xff, 0xff, 0xff, 0x7f, */ \ + /* REPORT_SIZE (32)*/\ + 0x75, 0x20,\ + /* REPORT_COUNT */\ + 0x95, count,\ +/* INPUT (Data,Var,Abs)*/\ + 0x81, 0x02, +#define HIDDESC_32B_ENTRY_SIZE 16 // 16 bytes more for range definition + + +#define HIDDESC_GAMEPAD_16B \ + 0xa1, 0x00, /* COLLECTION (Physical)*/\ + 0x85, 0x01, /* REPORT_ID (1)*/\ + 0x05, 0x09, /* USAGE_PAGE (Button)*/\ + 0x19, 0x01, /* USAGE_MINIMUM (Button 1)*/\ + 0x29, 0x40, /* USAGE_MAXIMUM (Button 64)*/\ + 0x15, 0x00, /* LOGICAL_MINIMUM (0)*/\ + 0x25, 0x01, /* LOGICAL_MAXIMUM (1)*/\ + 0x95, 0x40, /* REPORT_COUNT (64)*/\ + 0x75, 0x01, /* REPORT_SIZE (1)*/\ + 0x81, 0x02, /* INPUT (Data,Var,Abs)*/\ + 0x05, 0x01, /* USAGE_PAGE (Generic Desktop)*/\ + 0x09, HID_USAGE_DESKTOP_X, /* USAGE (X)*/\ + 0x09, HID_USAGE_DESKTOP_Y, /* USAGE (Y)*/\ + 0x09, HID_USAGE_DESKTOP_Z, /* USAGE (Z)*/\ + 0x09, HID_USAGE_DESKTOP_RX, /* USAGE (Rx)*/\ + 0x09, HID_USAGE_DESKTOP_RY, /* USAGE (Ry)*/\ + 0x09, HID_USAGE_DESKTOP_RZ, /* USAGE (Rz)*/\ + 0x09, HID_USAGE_DESKTOP_DIAL, /* USAGE (Dial)*/\ + 0x09, HID_USAGE_DESKTOP_SLIDER, /* USAGE (Slider)*/\ + 0x16, 0x01, 0x80, /* LOGICAL_MINIMUM (-32767)*/\ + 0x26, 0xff, 0x7f, /* LOGICAL_MAXIMUM (32767)*/\ + 0x75, 0x10, /* REPORT_SIZE (16)*/\ + 0x95, 0x08, /* REPORT_COUNT (8)*/\ + 0x81, 0x02, /* INPUT (Data,Var,Abs)*/\ + 0xc0 +#define HIDDESC_GAMEPAD_16B_SIZE 51 + +// Define workaround because we can't have conditionals in macros +#if MAX_AXIS == 1 +#define HIDDESC_GPENTRY_32B_1 0x09, HID_USAGE_DESKTOP_X, /* USAGE (X)*/\ + HIDDESC_32B_ENTRY(0x01) +#else +#define HIDDESC_GPENTRY_32B_1 0x09, HID_USAGE_DESKTOP_X, /* USAGE (X)*/ +#endif +#if MAX_AXIS == 2 +#define HIDDESC_GPENTRY_32B_2 0x09, HID_USAGE_DESKTOP_Y, /* USAGE (Y)*/\ + HIDDESC_32B_ENTRY(0x02) +#else +#define HIDDESC_GPENTRY_32B_2 0x09, HID_USAGE_DESKTOP_Y, /* USAGE (Y)*/ +#endif +#if MAX_AXIS == 3 +#define HIDDESC_GPENTRY_32B_3 0x09, HID_USAGE_DESKTOP_Z, /* USAGE (Z)*/\ + HIDDESC_32B_ENTRY(0x03) +#else +#define HIDDESC_GPENTRY_32B_3 0x09, HID_USAGE_DESKTOP_Z, /* USAGE (Z)*/ #endif +#define HIDDESC_GAMEPAD_32B \ + 0xa1, 0x00, /* COLLECTION (Physical)*/\ + 0x85, 0x01, /* REPORT_ID (1)*/\ + 0x05, 0x09, /* USAGE_PAGE (Button)*/\ + 0x19, 0x01, /* USAGE_MINIMUM (Button 1)*/\ + 0x29, 0x40, /* USAGE_MAXIMUM (Button 64)*/\ + 0x15, 0x00, /* LOGICAL_MINIMUM (0)*/\ + 0x25, 0x01, /* LOGICAL_MAXIMUM (1)*/\ + 0x95, 0x40, /* REPORT_COUNT (64)*/\ + 0x75, 0x01, /* REPORT_SIZE (1)*/\ + 0x81, 0x02, /* INPUT (Data,Var,Abs)*/\ + 0x05, 0x01, /* USAGE_PAGE (Generic Desktop)*/\ + HIDDESC_GPENTRY_32B_1 \ + HIDDESC_GPENTRY_32B_2 \ + HIDDESC_GPENTRY_32B_3 \ + 0x09, HID_USAGE_DESKTOP_RX, /* USAGE (Rx)*/\ + 0x09, HID_USAGE_DESKTOP_RY, /* USAGE (Ry)*/\ + 0x09, HID_USAGE_DESKTOP_RZ, /* USAGE (Rz)*/\ + 0x09, HID_USAGE_DESKTOP_DIAL, /* USAGE (Dial)*/\ + 0x09, HID_USAGE_DESKTOP_SLIDER, /* USAGE (Slider)*/\ + 0x16, 0x01, 0x80, /* LOGICAL_MINIMUM (-32767)*/\ + 0x26, 0xff, 0x7f, /* LOGICAL_MAXIMUM (32767)*/\ + 0x75, 0x10, /* REPORT_SIZE (16)*/\ + 0x95, 0x08-MAX_AXIS, /* REPORT_COUNT (8-32baxes)*/\ + 0x81, 0x02, /* INPUT (Data,Var,Abs)*/\ + 0xc0 +#define HIDDESC_GAMEPAD_32B_SIZE HIDDESC_GAMEPAD_16B_SIZE + HIDDESC_32B_ENTRY_SIZE +// Control reports for HID command interface +#define HIDDESC_CTRL_REP(DIR) /* INPUT or OUTPUT*/\ + 0x85,HID_ID_HIDCMD, /* Report ID*/\ + 0x09, 0x01, /* USAGE (Vendor)*/\ + 0x15, 0x00, /* LOGICAL_MINIMUM (0)*/\ + 0x26, 0x04, 0x00, /* Logical Maximum 4*/\ + 0x75, 0x08, /* REPORT_SIZE (8)*/\ + 0x95, 0x01, /* REPORT_COUNT (1)*/\ + HID_##DIR(1), /* INPUT (Data,Var,Abs)*/\ + \ + 0x09, 0x02, /* USAGE (Vendor) class address*/\ + 0x75, 0x10, /* REPORT_SIZE (16)*/\ + 0x95, 0x01, /* REPORT_COUNT (1)*/\ + HID_##DIR(1), /* INPUT (Data,Var,Abs)*/\ + \ + 0x09, 0x03, /* USAGE (Vendor) class instance*/\ + 0x75, 0x08, /* REPORT_SIZE (8)*/\ + 0x95, 0x01, /* REPORT_COUNT (1)*/\ + HID_##DIR(1), /* INPUT (Data,Var,Abs)*/\ + \ + 0x09, 0x04, /* USAGE (Vendor) cmd*/\ + 0x75, 0x20, /* REPORT_SIZE (32)*/\ + 0x95, 0x01, /* REPORT_COUNT (1)*/\ + HID_##DIR(1), /* INPUT (Data,Var,Abs)*/\ + \ + 0x09, 0x05, /* USAGE (Vendor)*/\ + 0x75, 0x40, /* REPORT_SIZE (64) value*/\ + 0x95, 0x01, /* REPORT_COUNT (1)*/\ + HID_##DIR(1), /* INPUT (Data,Var,Abs)*/\ + \ + 0x09, 0x06, /* USAGE (Vendor) address*/\ + 0x75, 0x40, /* REPORT_SIZE (64)*/\ + 0x95, 0x01, /* REPORT_COUNT (1)*/\ + HID_##DIR(1) /* INPUT (Data,Var,Abs)*/ +#define HIDDESC_CTRL_REPORTS \ + 0x06, 0x00, 0xFF, /* USAGE_PAGE (Vendor)*/\ + 0x09, 0x00, /* USAGE (Vendor)*/\ + 0xA1, 0x01, /* Collection (Application)*/\ + HIDDESC_CTRL_REP(OUTPUT),\ + HIDDESC_CTRL_REP(INPUT),\ + 0xc0 /* END_COLLECTION*/ +#define HIDDESC_CTRL_REPORTS_SIZE 118 + +#define HIDDESC_FFB_STATEREP \ + 0x05,0x0F, /* Usage Page Physical Interface*/ \ + 0x09,0x92, /* Usage PID State report*/\ + 0xA1,0x02, /* Collection Datalink (logical)*/\ + 0x85,HID_ID_STATE+FFB_ID_OFFSET, /* Report ID 2*/\ +/* 0x09,0x22, Usage Effect Block Index*/\ +/* 0x15,0x01, Logical Minimum 1*/\ +/* 0x25,MAX_EFFECTS, Logical Maximum 28h (40d)*/\ +/* 0x35,0x01, Physical Minimum 1*/\ +/* 0x45,MAX_EFFECTS, Physical Maximum 28h (40d)*/\ +/* 0x75,0x08, Report Size 8*/\ +/* 0x95,0x01, Report Count 1*/\ +/* 0x81,0x02, Input (Variable)*/\ + 0x09,0x9F, /* Usage Device is Pause*/\ + 0x09,0xA0, /* Usage Actuators Enabled*/\ + 0x09,0xA4, /* Usage Safety Switch*/\ + 0x09,0xA6, /* Usage Actuator Power*/\ + 0x09,0x94, /* Usage Effect Playing*/\ + /* 0x15,0x00, Logical Minimum 0*/\ + /* 0x25,0x01, Logical Maximum 1*/\ + /* 0x35,0x00, Physical Minimum 0*/\ + /* 0x45,0x01, Physical Maximum 1*/\ + /* 0x75,0x01, Report Size 1*/\ + /* 0x95,0x01, Report Count 1*/\ + /* 0x81,0x02, Input (Variable)*/\ + 0x15,0x00, /* Logical Minimum 0*/\ + 0x25,0x01, /* Logical Maximum 1*/\ + 0x35,0x00, /* Physical Minimum 0*/\ + 0x45,0x01, /* Physical Maximum 1*/\ + 0x75,0x01, /* Report Size 1*/\ + 0x95,0x05, /* Report Count 4*/\ + 0x81,0x02, /* Input (Variable)*/\ + 0x95,0x03, /* Report Count 3*/\ + 0x81,0x03, /* Input (Constant, Variable)*/\ + 0xC0 // End Collection +#define HIDDESC_FFB_STATEREP_SIZE 37 + +/* +Output +Collection Datalink: +Usage Set Effect Report + +ID:1 +Effect Block Index: 8bit + +subcollection Effect Type +12 effect types, 8bit each + +*/ +#define HIDDESC_FFB_SETEFREP \ + 0x09,0x21, /* Usage Set Effect Report*/\ + 0xA1,0x02, /* Collection Datalink (Logical)*/\ + 0x85,HID_ID_EFFREP+FFB_ID_OFFSET, /* Report ID 1*/\ + 0x09,0x22, /* Usage Effect Block Index*/\ + 0x15,0x01, /* Logical Minimum 1*/\ + 0x25,MAX_EFFECTS, /* Logical Maximum 28h (40d)*/\ + 0x35,0x01, /* Physical Minimum 1*/\ + 0x45,MAX_EFFECTS, /* Physical Maximum 28h (40d)*/\ + 0x75,0x08, /* Report Size 8*/\ + 0x95,0x01, /* Report Count 1*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0x09,0x25, /* Usage Effect Type*/\ + 0xA1,0x02, /* Collection Datalink*/\ + 0x09, HID_USAGE_CONST, /* Usage ET Constant Force*/\ + 0x09, HID_USAGE_RAMP, /* Usage ET Ramp*/\ + 0x09, HID_USAGE_SQUR, /* Usage ET Square*/\ + 0x09, HID_USAGE_SINE, /* Usage ET Sine*/\ + 0x09, HID_USAGE_TRNG, /* Usage ET Triangle*/\ + 0x09, HID_USAGE_STUP, /* Usage ET Sawtooth Up*/\ + 0x09, HID_USAGE_STDN, /* Usage ET Sawtooth Down*/\ + 0x09, HID_USAGE_SPRNG, /* Usage ET Spring*/\ + 0x09, HID_USAGE_DMPR, /* Usage ET Damper*/\ + 0x09, HID_USAGE_INRT, /* Usage ET Inertia*/\ + 0x09, HID_USAGE_FRIC, /* Usage ET Friction*/\ + /* 0x09, 0x28, // Usage ET Custom Force Data*/\ + 0x25,0x0B, /* Logical Maximum Bh (11d)*/\ + 0x15,0x01, /* Logical Minimum 1*/\ + 0x35,0x01, /* Physical Minimum 1*/\ + 0x45,0x0B, /* Physical Maximum Bh (11d)*/\ + 0x75,0x08, /* Report Size 8*/\ + 0x95,0x01, /* Report Count 1*/\ + 0x91,0x00, /* Output*/\ + 0xC0 , /* End Collection*/\ + 0x09,0x50, /* Usage Duration*/\ + 0x09,0x54, /* Usage Trigger Repeat Interval*/\ + 0x09,0x51, /* Usage Sample Period*/\ + 0x09,0xA7, /* Usage Start Delay*/\ + 0x15,0x00, /* Logical Minimum 0*/\ + 0x26,0xFF,0x7F, /* Logical Maximum 7FFFh (32767d)*/\ + 0x35,0x00, /* Physical Minimum 0*/\ + 0x46,0xFF,0x7F, /* Physical Maximum 7FFFh (32767d)*/\ + 0x66,0x03,0x10, /* Unit 1003h (4099d)*/\ + 0x55,0xFD, /* Unit Exponent FDh (253d)*/\ + 0x75,0x10, /* Report Size 10h (16d)*/\ + 0x95,0x04, /* Report Count 4*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0x55,0x00, /* Unit Exponent 0*/\ + 0x66,0x00,0x00, /* Unit 0*/\ + 0x09,0x52, /* Usage Gain*/\ + 0x15,0x00, /* Logical Minimum 0*/\ + 0x26,0xFF,0x00, /* Logical Maximum FFh (255d) // TODO scaling?*/\ + 0x35,0x00, /* Physical Minimum 0*/\ + 0x46,0x10,0x27, /* Physical Maximum 2710h (10000d)*/\ + 0x75,0x08, /* Report Size 8*/\ + 0x95,0x01, /* Report Count 1*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0x09,0x53, /* Usage Trigger Button*/\ + 0x15,0x01, /* Logical Minimum 1*/\ + 0x25,0x08, /* Logical Maximum 8*/\ + 0x35,0x01, /* Physical Minimum 1*/\ + 0x45,0x08, /* Physical Maximum 8*/\ + 0x75,0x08, /* Report Size 8*/\ + 0x95,0x01, /* Report Count 1*/\ + 0x91,0x02 // Output (Variable) +#define HIDDESC_FFB_SETEFREP_SIZE 131 + +#define HIDDESC_FFB_SETENVREP \ + /* Envelope Report Definition*/\ + 0x09,0x5A, /* Usage Set Envelope Report*/\ + 0xA1,0x02, /* Collection Datalink*/\ + 0x85,HID_ID_ENVREP+FFB_ID_OFFSET, /* Report ID 2*/\ + 0x09,0x22, /* Usage Effect Block Index*/\ + 0x15,0x01, /* Logical Minimum 1*/\ + 0x25,MAX_EFFECTS, /* Logical Maximum 28h (40d)*/\ + 0x35,0x01, /* Physical Minimum 1*/\ + 0x45,MAX_EFFECTS, /* Physical Maximum 28h (40d)*/\ + 0x75,0x08, /* Report Size 8*/\ + 0x95,0x01, /* Report Count 1*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0x09,0x5B, /* Usage Attack Level*/\ + 0x09,0x5D, /* Usage Fade Level*/\ + 0x16,0x00,0x00, /* Logical Minimum 0*/\ + 0x26,0xFF,0x7F, /* Logical Maximum 7FFFh (32767d)*/\ + 0x36,0x00,0x00, /* Physical Minimum 0*/\ + 0x46,0xFF,0x7F, /* Physical Maximum 7FFFh (32767d)*/\ + 0x75,0x10, /* Report Size 16*/\ + 0x95,0x02, /* Report Count 2*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0x09, 0x5C, /* Usage Attack Time*/\ + 0x09, 0x5E, /* Usage Fade Time*/\ + 0x66, 0x03, 0x10, /* Unit 1003h (English Linear, Seconds)*/\ + 0x55, 0xFD, /* Unit Exponent FDh (X10^-3 ==> Milisecond)*/\ + 0x27, 0xFF, 0x7F, 0x00, 0x00, /* Logical Maximum FFFFFFFFh (4294967295)*/\ + 0x47, 0xFF, 0x7F, 0x00, 0x00, /* Physical Maximum FFFFFFFFh (4294967295)*/\ + 0x75, 0x20, /* Report Size 20h (32d)*/\ + 0x91, 0x02, /* Output (Variable)*/\ + 0x45, 0x00, /* Physical Maximum 0*/\ + 0x66,0x00,0x00, /* Unit 0*/\ + 0x55,0x00, /* Unit Exponent 0*/\ + 0xC0 /* End Collection*/ +#define HIDDESC_FFB_SETENVREP_SIZE 75 + +// Contains axis dependant parts. not used +#define HIDDESC_FFB_SETCONDREP \ + 0x09,0x5F, /* Usage Set Condition Report*/\ + 0xA1,0x02, /* Collection Datalink*/\ + 0x85,HID_ID_CONDREP+FFB_ID_OFFSET, /* Report ID 3*/\ + 0x09,0x22, /* Usage Effect Block Index*/\ + 0x15,0x01, /* Logical Minimum 1*/\ + 0x25,MAX_EFFECTS, /* Logical Maximum 28h (40d)*/\ + 0x35,0x01, /* Physical Minimum 1*/\ + 0x45,MAX_EFFECTS, /* Physical Maximum 28h (40d)*/\ + 0x75,0x08, /* Report Size 8*/\ + 0x95,0x01, /* Report Count 1*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0x09,0x23, /* Usage Parameter Block Offset*/\ + 0x15,0x00, /* Logical Minimum 0*/\ + 0x25,0x03, /* Logical Maximum 3*/\ + 0x35,0x00, /* Physical Minimum 0*/\ + 0x45,0x03, /* Physical Maximum 3*/\ + 0x75,0x04, /* Report Size 4*/\ + 0x95,0x01, /* Report Count 1*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0x09,0x58, /* Usage Type Specific Block Off...*/\ + 0xA1,0x02, /* Collection Datalink*/\ + 0x0B,0x01,0x00,0x0A,0x00, /* Usage Ordinals: Instance 1*/\ + 0x0B,0x02,0x00,0x0A,0x00, /* Usage Ordinals: Instance 2*/\ + 0x75,0x02, /* Report Size 2*/\ + 0x95,0x02, /* Report Count 2*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0xC0 , /* End Collection*/\ + 0x16,0x00, 0x80, /* Logical Minimum 7FFFh (-32767d)*/\ + 0x26,0xff, 0x7f, /* Logical Maximum 7FFFh (32767d)*/\ + 0x36,0x00, 0x80, /* Physical Minimum 7FFFh (-32767d)*/\ + 0x46,0xff, 0x7f, /* Physical Maximum 7FFFh (32767d)*/\ +\ + 0x09,0x60, /* Usage CP Offset*/\ + 0x75,0x10, /* Report Size 16*/\ + 0x95,0x01, /* Report Count 1*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0x36,0x00, 0x80, /* Physical Minimum (-32768)*/\ + 0x46,0xff, 0x7f, /* Physical Maximum (32767)*/\ + 0x09,0x61, /* Usage Positive Coefficient*/\ + 0x09,0x62, /* Usage Negative Coefficient*/\ + 0x95,0x02, /* Report Count 2*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0x16,0x00,0x00, /* Logical Minimum 0*/\ + 0x26,0xff, 0x7f, /* Logical Maximum (32767)*/\ + 0x36,0x00,0x00, /* Physical Minimum 0*/\ + 0x46,0xff, 0x7f, /* Physical Maximum (32767)*/\ + 0x09,0x63, /* Usage Positive Saturation*/\ + 0x09,0x64, /* Usage Negative Saturation*/\ + 0x75,0x10, /* Report Size 16*/\ + 0x95,0x02, /* Report Count 2*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0x09,0x65, /* Usage Dead Band*/\ + 0x46,0xff, 0x7f, /* Physical Maximum (32767)*/\ + 0x95,0x01, /* Report Count 1*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0xC0 /* End Collection*/ +#define HIDDESC_FFB_SETCONDREP_SIZE 125 + +#define HIDDESC_FFB_SETPERIODICREP \ + 0x09,0x6E, /* Usage Set Periodic Report*/\ + 0xA1,0x02, /* Collection Datalink*/\ + 0x85,HID_ID_PRIDREP+FFB_ID_OFFSET, /* Report ID 4*/\ + 0x09,0x22, /* Usage Effect Block Index*/\ + 0x15,0x01, /* Logical Minimum 1*/\ + 0x25,MAX_EFFECTS, /* Logical Maximum 28h (40d)*/\ + 0x35,0x01, /* Physical Minimum 1*/\ + 0x45,MAX_EFFECTS, /* Physical Maximum 28h (40d)*/\ + 0x75,0x08, /* Report Size 8*/\ + 0x95,0x01, /* Report Count 1*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0x09,0x70, /* Usage Magnitude*/\ + 0x16,0x00,0x00, /* Logical Minimum 0*/\ + 0x26,0xff, 0x7f, /* Logical Maximum 7FFFh (32767d)*/\ + 0x36,0x00,0x00, /* Physical Minimum 0*/\ + 0x26,0xff, 0x7f, /* Logical Maximum 7FFFh (32767d)*/\ + 0x75,0x10, /* Report Size 16*/\ + 0x95,0x01, /* Report Count 1*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0x09, 0x6F, /* Usage Offset*/\ + 0x16,0x00, 0x80, /* Logical Minimum 7FFFh (-32767d)*/\ + 0x26,0xff, 0x7f, /* Logical Maximum 7FFFh (32767d)*/\ + 0x36,0x00, 0x80, /* Physical Minimum 7FFFh (-32767d)*/\ + 0x46,0xff, 0x7f, /* Physical Maximum 7FFFh (32767d)*/\ + 0x95, 0x01, /* Report Count 1*/\ + 0x75, 0x10, /* Report Size 16*/\ + 0x91, 0x02, /* Output (Variable)*/\ + 0x09, 0x71, /* Usage Phase*/\ + 0x66, 0x14, 0x00, /* Unit 14h (Eng Rotation, Degrees)*/\ + 0x55, 0xFE, /* Unit Exponent FEh (X10^-2)*/\ + 0x15, 0x00, /* Logical Minimum 0*/\ + 0x27, 0x9F, 0x8C, 0x00, 0x00, /* Logical Maximum 8C9Fh (35999d)*/\ + 0x35, 0x00, /* Physical Minimum 0*/\ + 0x47, 0x9F, 0x8C, 0x00, 0x00, /* Physical Maximum 8C9Fh (35999d)*/\ + 0x75, 0x10, /* Report Size 16*/\ + 0x95, 0x01, /* Report Count 1*/\ + 0x91, 0x02, /* Output (Variable)*/\ + 0x09, 0x72, /* Usage Period*/\ + 0x15, 0x01, /* Logical Minimum 1*/\ + 0x27, 0xFF, 0x7F, 0x00, 0x00, /* Logical Maximum 7FFFh (32K)*/\ + 0x35, 0x01, /* Physical Minimum 1*/\ + 0x47, 0xFF, 0x7F, 0x00, 0x00, /* Physical Maximum 7FFFh (32K)*/\ + 0x66, 0x03, 0x10, /* Unit 1003h (English Linear, Seconds)*/\ + 0x55, 0xFD, /* Unit Exponent FDh (X10^-3 ==> Millisecond)*/\ + 0x75, 0x20, /* Report Size 20h (32)*/\ + 0x95, 0x01, /* Report Count 1*/\ + 0x91, 0x02, /* Output (Variable)*/\ + 0x66, 0x00, 0x00, /* Unit 0*/\ + 0x55,0x00, /* Unit Exponent 0*/\ + 0xC0 /* End Collection*/ +#define HIDDESC_FFB_SETPERIODICREP_SIZE 122 + +#define HIDDESC_FFB_SETCFREP \ + 0x09,0x73, /* Usage Set Constant Force Report*/\ + 0xA1,0x02, /* Collection Datalink*/\ + 0x85,HID_ID_CONSTREP+FFB_ID_OFFSET, /* Report ID 5*/\ + 0x09,0x22, /* Usage Effect Block Index*/\ + 0x15,0x01, /* Logical Minimum 1*/\ + 0x25,MAX_EFFECTS, /* Logical Maximum 28h (40d)*/\ + 0x35,0x01, /* Physical Minimum 1*/\ + 0x45,MAX_EFFECTS, /* Physical Maximum 28h (40d)*/\ + 0x75,0x08, /* Report Size 8*/\ + 0x95,0x01, /* Report Count 1*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0x09,0x70, /* Usage Magnitude*/\ + 0x16,0x01, 0x80, /* Logical Minimum -7FFFh (-32767d)*/\ + 0x26,0xff, 0x7f, /* Logical Maximum 7FFFh (32767d)*/\ + 0x36,0x01, 0x80, /* Physical Minimum -7FFFh (-32767d)*/\ + 0x46,0xff, 0x7f, /* Physical Maximum 7FFFh (32767d)*/\ + 0x75, 0x10, /* Report Size 10h (16d)*/\ + 0x95,0x01, /* Report Count 1*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0xC0 /* End Collection*/ +#define HIDDESC_FFB_SETCFREP_SIZE 43 + +#define HIDDESC_FFB_SETRAMPREP \ + 0x09,0x74, /* Usage Set Ramp Force Report*/\ + 0xA1,0x02, /* Collection Datalink*/\ + 0x85,HID_ID_RAMPREP+FFB_ID_OFFSET, /* Report ID 6*/\ + 0x09,0x22, /* Usage Effect Block Index*/\ + 0x15,0x01, /* Logical Minimum 1*/\ + 0x25,MAX_EFFECTS, /* Logical Maximum 28h (40d)*/\ + 0x35,0x01, /* Physical Minimum 1*/\ + 0x45,MAX_EFFECTS, /* Physical Maximum 28h (40d)*/\ + 0x75,0x08, /* Report Size 8*/\ + 0x95,0x01, /* Report Count 1*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0x09,0x75, /* Usage Ramp Start*/\ + 0x09,0x76, /* Usage Ramp End*/\ + 0x16,0x00, 0x80, /* Logical Minimum 7FFFh (-32767d)*/\ + 0x26,0xff, 0x7f, /* Logical Maximum 7FFFh (32767d)*/\ + 0x36,0x00, 0x80, /* Physical Minimum 7FFFh (-32767d)*/\ + 0x46,0xff, 0x7f, /* Physical Maximum 7FFFh (32767d)*/\ + 0x75,0x10, /* Report Size 16*/\ + 0x95,0x02, /* Report Count 2*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0xC0 /* End Collection*/ +#define HIDDESC_FFB_SETRAMPREP_SIZE 45 +// not to be used yet +#define HIDDESC_FFB_CUSTOMFORCEREP \ +/* 0x09,0x68, // Usage Custom Force Data Report*/\ +/* 0xA1,0x02, // Collection Datalink*/\ +/* 0x85,HID_ID_CSTMREP+FFB_ID_OFFSET, // Report ID 7*/\ +/* 0x09,0x22, // Usage Effect Block Index*/\ +/* 0x15,0x01, // Logical Minimum 1*/\ +/* 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d)*/\ +/* 0x35,0x01, // Physical Minimum 1*/\ +/* 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d)*/\ +/* 0x75,0x08, // Report Size 8*/\ +/* 0x95,0x01, // Report Count 1*/\ +/* 0x91,0x02, // Output (Variable)*/\ +/* 0x09,0x6C, // Usage Custom Force Data Offset*/\ +/* 0x15,0x00, // Logical Minimum 0*/\ +/* 0x26,0x10,0x27, // Logical Maximum 2710h (10000d)*/\ +/* 0x35,0x00, // Physical Minimum 0*/\ +/* 0x46,0x10,0x27, // Physical Maximum 2710h (10000d)*/\ +/* 0x75,0x10, // Report Size 10h (16d)*/\ +/* 0x95,0x01, // Report Count 1*/\ +/* 0x91,0x02, // Output (Variable)*/\ +/* 0x09,0x69, // Usage Custom Force Data*/\ +/* 0x15,0x81, // Logical Minimum 81h (-127d)*/\ +/* 0x25,0x7F, // Logical Maximum 7Fh (127d)*/\ +/* 0x35,0x00, // Physical Minimum 0*/\ +/* 0x46,0xFF,0x00, // Physical Maximum FFh (255d)*/\ +/* 0x75,0x08, // Report Size 8*/\ +/* 0x95,0x0C, // Report Count Ch (12d)*/\ +/* 0x92,0x02,0x01, // Output (Variable, Buffered)*/\ +/* 0xC0 , // End Collection*/\ +/* 0x09,0x66, // Usage Download Force Sample*/\ +/* 0xA1,0x02, // Collection Datalink*/\ +/* 0x85,HID_ID_SMPLREP+FFB_ID_OFFSET, // Report ID 8*/\ +/* 0x05,0x01, // Usage Page Generic Desktop*/\ +/* 0x09,0x30, // Usage X*/\ +/* 0x09,0x31, // Usage Y*/\ +/* 0x15,0x81, // Logical Minimum 81h (-127d)*/\ +/* 0x25,0x7F, // Logical Maximum 7Fh (127d)*/\ +/* 0x35,0x00, // Physical Minimum 0*/\ +/* 0x46,0xFF,0x00, // Physical Maximum FFh (255d)*/\ +/* 0x75,0x08, // Report Size 8*/\ +/* 0x95,0x02, // Report Count 2*/\ +/* 0x91,0x02, // Output (Variable)*/\ +/* 0xC0 , // End Collection*/ +#define HIDDESC_FFB_EFOPREP \ + 0x05,0x0F, /* Usage Page Physical Interface*/\ + 0x09,0x77, /* Usage Effect Operation Report*/\ + 0xA1,0x02, /* Collection Datalink*/\ + 0x85,HID_ID_EFOPREP+FFB_ID_OFFSET, /* Report ID Ah (10d)*/\ + 0x09,0x22, /* Usage Effect Block Index*/\ + 0x15,0x01, /* Logical Minimum 1*/\ + 0x25,MAX_EFFECTS, /* Logical Maximum 28h (40d)*/\ + 0x35,0x01, /* Physical Minimum 1*/\ + 0x45,MAX_EFFECTS, /* Physical Maximum 28h (40d)*/\ + 0x75,0x08, /* Report Size 8*/\ + 0x95,0x01, /* Report Count 1*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0x09,0x78, /* Usage Effect Operation*/\ + 0xA1,0x02, /* Collection Datalink*/\ + 0x09,0x79, /* Usage Op Effect Start*/\ + 0x09,0x7A, /* Usage Op Effect Start Solo*/\ + 0x09,0x7B, /* Usage Op Effect Stop*/\ + 0x15,0x01, /* Logical Minimum 1*/\ + 0x25,0x03, /* Logical Maximum 3*/\ + 0x75,0x08, /* Report Size 8*/\ + 0x95,0x01, /* Report Count 1*/\ + 0x91,0x00, /* Output*/\ + 0xC0 , /* End Collection*/\ + 0x09,0x7C, /* Usage Loop Count*/\ + 0x15,0x00, /* Logical Minimum 0*/\ + 0x26,0xFF,0x00, /* Logical Maximum FFh (255d)*/\ + 0x35,0x00, /* Physical Minimum 0*/\ + 0x46,0xFF,0x00, /* Physical Maximum FFh (255d)*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0xC0 /* End Collection*/ +#define HIDDESC_FFB_EFOPREP_SIZE 60 +#define HIDDESC_FFB_BLOCKFREEREP \ + 0x09,0x90, /* Usage PID Block Free Report*/\ + 0xA1,0x02, /* Collection Datalink*/\ + 0x85,HID_ID_BLKFRREP+FFB_ID_OFFSET, /* Report ID Bh (11d)*/\ + 0x09,0x22, /* Usage Effect Block Index*/\ + 0x15,0x01, /* Logical Minimum 1*/\ + 0x25,MAX_EFFECTS, /* Logical Maximum 28h (40d)*/\ + 0x35,0x01, /* Physical Minimum 1*/\ + 0x45,MAX_EFFECTS, /* Physical Maximum 28h (40d)*/\ + 0x75,0x08, /* Report Size 8*/\ + 0x95,0x01, /* Report Count 1*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0xC0 /* End Collection*/ +#define HIDDESC_FFB_BLOCKFREEREP_SIZE 23 +#define HIDDESC_FFB_DEVCTRLREP \ + 0x09,0x95, /* Usage PID Device Control (0x96?)*/\ + 0xA1,0x02, /* Collection Datalink*/\ + 0x85,HID_ID_CTRLREP+FFB_ID_OFFSET, /* Report ID Ch (12d)*/\ + 0x09,0x96, /* Usage PID Device Control (0x96?)*/\ + 0xA1,0x02, /* Collection Datalink*/\ +\ + 0x09,0x97, /* Usage DC Enable Actuators*/\ + 0x09,0x98, /* Usage DC Disable Actuators*/\ + 0x09,0x99, /* Usage DC Stop All Effects*/\ + 0x09,0x9A, /* Usage DC Device Reset*/\ + 0x09,0x9B, /* Usage DC Device Pause*/\ + 0x09,0x9C, /* Usage DC Device Continue*/\ +\ +\ +\ + 0x15,0x01, /* Logical Minimum 1*/\ + 0x25,0x06, /* Logical Maximum 6*/\ + 0x75,0x01, /* Report Size 1*/\ + 0x95,0x08, /* Report Count 8*/\ + 0x91,0x02, /* Output*/\ +\ + 0xC0 , /* End Collection*/\ + 0xC0 , /* End Collection*/\ + 0x09,0x7D, /* Usage Device Gain Report*/\ + 0xA1,0x02, /* Collection Datalink*/\ + 0x85,HID_ID_GAINREP+FFB_ID_OFFSET, /* Report ID Dh (13d)*/\ + 0x09,0x7E, /* Usage Device Gain*/\ + 0x15,0x00, /* Logical Minimum 0*/\ + 0x26,0xFF,0x00, /* Logical Maximum FFh (255d)*/\ + 0x35,0x00, /* Physical Minimum 0*/\ + 0x46,0x10,0x27, /* Physical Maximum 2710h (10000d)*/\ + 0x75,0x08, /* Report Size 8*/\ + 0x95,0x01, /* Report Count 1*/\ + 0x91,0x02, /* Output (Variable)*/\ + 0xC0 /* End Collection*/ +#define HIDDESC_FFB_DEVCTRLREP_SIZE 59 +// Do not use yet +#define HIDDESC_FFB_SETCUSTFORCEREP \ +/* 0x09,0x6B, // Usage Set Custom Force Report*/\ +/* 0xA1,0x02, // Collection Datalink*/\ +/* 0x85,HID_ID_SETCREP+FFB_ID_OFFSET, // Report ID Eh (14d)*/\ +/* 0x09,0x22, // Usage Effect Block Index*/\ +/* 0x15,0x01, // Logical Minimum 1*/\ +/* 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d)*/\ +/* 0x35,0x01, // Physical Minimum 1*/\ +/* 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d)*/\ +/* 0x75,0x08, // Report Size 8*/\ +/* 0x95,0x01, // Report Count 1*/\ +/* 0x91,0x02, // Output (Variable)*/\ +/* 0x09,0x6D, // Usage Sample Count*/\ +/* 0x15,0x00, // Logical Minimum 0*/\ +/* 0x26,0xFF,0x00, // Logical Maximum FFh (255d)*/\ +/* 0x35,0x00, // Physical Minimum 0*/\ +/* 0x46,0xFF,0x00, // Physical Maximum FFh (255d)*/\ +/* 0x75,0x08, // Report Size 8*/\ +/* 0x95,0x01, // Report Count 1*/\ +/* 0x91,0x02, // Output (Variable)*/\ +/* 0x09,0x51, // Usage Sample Period*/\ +/* 0x66,0x03,0x10, // Unit 1003h (4099d)*/\ +/* 0x55,0xFD, // Unit Exponent FDh (253d)*/\ +/* 0x15,0x00, // Logical Minimum 0*/\ +/* 0x26,0xFF,0x7F, // Logical Maximum 7FFFh (32767d)*/\ +/* 0x35,0x00, // Physical Minimum 0*/\ +/* 0x46,0xFF,0x7F, // Physical Maximum 7FFFh (32767d)*/\ +/* 0x75,0x10, // Report Size 10h (16d)*/\ +/* 0x95,0x01, // Report Count 1*/\ +/* 0x91,0x02, // Output (Variable)*/\ +/* 0x55,0x00, // Unit Exponent 0*/\ +/* 0x66,0x00,0x00, // Unit 0*/\ +/* 0xC0 // End Collection*/ +#define HIDDESC_FFB_NEWEFREP \ + 0x09,0xAB, /* Usage Create New Effect Report*/\ + 0xA1,0x02, /* Collection Datalink*/\ + 0x85,HID_ID_NEWEFREP+FFB_ID_OFFSET, /* Report ID 1*/\ + 0x09,0x25, /* Usage Effect Type*/\ + 0xA1,0x02, /* Collection Datalink*/\ + 0x09, HID_USAGE_CONST, /* Usage ET Constant Force*/\ + 0x09, HID_USAGE_RAMP, /* Usage ET Ramp*/\ + 0x09, HID_USAGE_SQUR, /* Usage ET Square*/\ + 0x09, HID_USAGE_SINE, /* Usage ET Sine*/\ + 0x09, HID_USAGE_TRNG, /* Usage ET Triangle*/\ + 0x09, HID_USAGE_STUP, /* Usage ET Sawtooth Up*/\ + 0x09, HID_USAGE_STDN, /* Usage ET Sawtooth Down*/\ + 0x09, HID_USAGE_SPRNG, /* Usage ET Spring*/\ + 0x09, HID_USAGE_DMPR, /* Usage ET Damper*/\ + 0x09, HID_USAGE_INRT, /* Usage ET Inertia*/\ + 0x09, HID_USAGE_FRIC, /* Usage ET Friction*/\ +/* 0x09, 0x28, // Usage ET Custom Force Data*/\ + 0x25,0x0B, /* Logical Maximum Ch (11d)*/\ + 0x15,0x01, /* Logical Minimum 1*/\ + 0x35,0x01, /* Physical Minimum 1*/\ + 0x45,0x0B, /* Physical Maximum Ch (11d)*/\ + 0x75,0x08, /* Report Size 8*/\ + 0x95,0x01, /* Report Count 1*/\ + 0xB1,0x00, /* Feature*/\ + 0xC0 , /* End Collection*/\ + 0x05,0x01, /* Usage Page Generic Desktop*/\ + 0x09,0x3B, /* Usage Reserved (Byte count)*/\ + 0x15,0x00, /* Logical Minimum 0*/\ + 0x26,0xFF,0x01, /* Logical Maximum 1FFh (511d)*/\ + 0x35,0x00, /* Physical Minimum 0*/\ + 0x46,0xFF,0x01, /* Physical Maximum 1FFh (511d)*/\ + 0x75,0x0A, /* Report Size Ah (10d)*/\ + 0x95,0x01, /* Report Count 1*/\ + 0xB1,0x02, /* Feature (Variable)*/\ + 0x75,0x06, /* Report Size 6*/\ + 0xB1,0x01, /* Feature (Constant)*/\ + 0xC0 /* End Collection*/ +#define HIDDESC_FFB_NEWEFREP_SIZE 72 + +#define HIDDESC_FFB_BLOCKLOADREP \ + 0x05,0x0F, /* Usage Page Physical Interface*/\ + 0x09,0x89, /* Usage Block Load Report*/\ + 0xA1,0x02, /* Collection Datalink*/\ + 0x85,HID_ID_BLKLDREP+FFB_ID_OFFSET, /* Report ID 0x12*/\ + 0x09,0x22, /* Usage Effect Block Index*/\ + 0x25,MAX_EFFECTS, /* Logical Maximum 28h (40d)*/\ + 0x15,0x01, /* Logical Minimum 1*/\ + 0x35,0x01, /* Physical Minimum 1*/\ + 0x45,MAX_EFFECTS, /* Physical Maximum 28h (40d)*/\ + 0x75,0x08, /* Report Size 8*/\ + 0x95,0x01, /* Report Count 1*/\ + 0xB1,0x02, /* Feature (Variable)*/\ + 0x09,0x8B, /* Usage Block Load Status*/\ + 0xA1,0x02, /* Collection Datalink*/\ + 0x09,0x8C, /* Usage Block Load Success*/\ + 0x09,0x8D, /* Usage Block Load Full*/\ + 0x09,0x8E, /* Usage Block Load Error*/\ + 0x15,0x01, /* Logical Minimum 1*/\ + 0x25,0x03, /* Logical Maximum 3*/\ + 0x35,0x01, /* Physical Minimum 1*/\ + 0x45,0x03, /* Physical Maximum 3*/\ + 0x75,0x08, /* Report Size 8*/\ + 0x95,0x01, /* Report Count 1*/\ + 0xB1,0x00, /* Feature*/\ + 0xC0 , /* End Collection*/\ + 0x09,0xAC, /* Usage Pool available*/\ + 0x15,0x00, /* Logical Minimum 0*/\ + 0x27,0xFF,0xFF,0x00,0x00, /* Logical Maximum FFFFh (65535d)*/\ + 0x35,0x00, /* Physical Minimum 0*/\ + 0x47,0xFF,0xFF,0x00,0x00, /* Physical Maximum FFFFh (65535d)*/\ + 0x75,0x10, /* Report Size 10h (16d)*/\ + 0x95,0x01, /* Report Count 1*/\ + 0xB1,0x00, /* Feature*/\ + 0xC0 // End Collection +#define HIDDESC_FFB_BLOCKLOADREP_SIZE 72 + +#define HIDDESC_FFB_POOLREP \ + 0x09,0x7F, /* Usage PID Pool Report*/\ + 0xA1,0x02, /* Collection Datalink*/\ + 0x85,HID_ID_POOLREP+FFB_ID_OFFSET, /* Report ID 0x13*/\ + 0x09,0x80, /* Usage RAM Pool size*/\ + 0x75,0x10, /* Report Size 10h (16d)*/\ + 0x95,0x01, /* Report Count 1*/\ + 0x15,0x00, /* Logical Minimum 0*/\ + 0x35,0x00, /* Physical Minimum 0*/\ + 0x27,0xFF,0xFF,0x00,0x00, /* Logical Maximum FFFFh (65535d)*/\ + 0x47,0xFF,0xFF,0x00,0x00, /* Physical Maximum FFFFh (65535d)*/\ + 0xB1,0x02, /* Feature (Variable)*/\ + 0x09,0x83, /* Usage Simultaneous Effects Max*/\ + 0x26,0xFF,0x00, /* Logical Maximum FFh (255d)*/\ + 0x46,0xFF,0x00, /* Physical Maximum FFh (255d)*/\ + 0x75,0x08, /* Report Size 8*/\ + 0x95,0x01, /* Report Count 1*/\ + 0xB1,0x02, /* Feature (Variable)*/\ + 0x09,0xA9, /* Usage Device Managed Pool*/\ + 0x09,0xAA, /* Usage Shared Parameter Blocks*/\ + 0x75,0x01, /* Report Size 1*/\ + 0x95,0x02, /* Report Count 2*/\ + 0x15,0x00, /* Logical Minimum 0*/\ + 0x25,0x01, /* Logical Maximum 1*/\ + 0x35,0x00, /* Physical Minimum 0*/\ + 0x45,0x01, /* Physical Maximum 1*/\ + 0xB1,0x02, /* Feature (Variable)*/\ + 0x75,0x06, /* Report Size 6*/\ + 0x95,0x01, /* Report Count 1*/\ + 0xB1,0x03, /* Feature (Constant, Variable)*/\ + 0xC0 // End Collection +#define HIDDESC_FFB_POOLREP_SIZE 67 + +#define HIDDESC_FFB_DESCSIZE HIDDESC_FFB_STATEREP_SIZE + HIDDESC_FFB_POOLREP_SIZE + HIDDESC_FFB_BLOCKLOADREP_SIZE + HIDDESC_FFB_NEWEFREP_SIZE + HIDDESC_FFB_DEVCTRLREP_SIZE + HIDDESC_FFB_BLOCKFREEREP_SIZE + HIDDESC_FFB_EFOPREP_SIZE + HIDDESC_FFB_SETEFREP_SIZE + HIDDESC_FFB_SETRAMPREP_SIZE + HIDDESC_FFB_SETCFREP_SIZE + HIDDESC_FFB_SETPERIODICREP_SIZE + HIDDESC_FFB_SETENVREP_SIZE + + -#define USB_HID_2FFB_REPORT_DESC_SIZE 1215//1213 #ifdef AXIS2_FFB_HID_DESC +#define USB_HID_2FFB_REPORT_DESC_SIZE HIDDESC_GAMEPAD_16B_SIZE + HIDDESC_CTRL_REPORTS_SIZE + HIDDESC_FFB_DESCSIZE + 7 + 108 + 125 extern const uint8_t hid_2ffb_desc[USB_HID_2FFB_REPORT_DESC_SIZE]; #endif +#ifdef AXIS2_FFB_HID_DESC_32B +#define USB_HID_2FFB_REPORT_DESC_32B_SIZE HIDDESC_GAMEPAD_32B_SIZE + HIDDESC_CTRL_REPORTS_SIZE + HIDDESC_FFB_DESCSIZE + 7 + 108 + 125 +extern const uint8_t hid_2ffb_desc_32b[USB_HID_2FFB_REPORT_DESC_32B_SIZE]; +#endif + +#ifdef AXIS1_FFB_HID_DESC +#define USB_HID_1FFB_REPORT_DESC_SIZE HIDDESC_GAMEPAD_16B_SIZE + HIDDESC_CTRL_REPORTS_SIZE + HIDDESC_FFB_DESCSIZE + 7 + 94 + 120 +extern const uint8_t hid_1ffb_desc[USB_HID_1FFB_REPORT_DESC_SIZE]; +#endif +#ifdef AXIS1_FFB_HID_DESC_32B +#define USB_HID_1FFB_REPORT_DESC_SIZE HIDDESC_GAMEPAD_32B_SIZE + HIDDESC_CTRL_REPORTS_SIZE + HIDDESC_FFB_DESCSIZE + 7 + 94 + 120 +extern const uint8_t hid_1ffb_desc_32b[USB_HID_1FFB_REPORT_DESC_32B_SIZE]; +#endif + -#define USB_HID_GAMEPAD_REPORT_DESC_SIZE 176 #ifdef FFB_HID_DESC_GAMEPAD +#define USB_HID_GAMEPAD_REPORT_DESC_SIZE HIDDESC_GAMEPAD_16B_SIZE + HIDDESC_CTRL_REPORTS_SIZE + 7 extern const uint8_t hid_gamepad_desc[USB_HID_GAMEPAD_REPORT_DESC_SIZE]; +#endif +#ifdef FFB_HID_DESC_GAMEPAD_32B +#define USB_HID_GAMEPAD_REPORT_DESC_32B_SIZE HIDDESC_GAMEPAD_32B_SIZE + HIDDESC_CTRL_REPORTS_SIZE + 7 +extern const uint8_t hid_gamepad_desc_32b[USB_HID_GAMEPAD_REPORT_DESC_32B_SIZE]; +#endif + +#ifdef HIDAXISRES_USE_32B_DESC + #endif +/** @}*/ #endif /* USB_INC_USB_HID_FFB_DESC_H_ */ diff --git a/Firmware/FFBoard/UserExtensions/Src/CanBridge.cpp b/Firmware/FFBoard/UserExtensions/Src/CanBridge.cpp index 9708e8908..5b013463c 100644 --- a/Firmware/FFBoard/UserExtensions/Src/CanBridge.cpp +++ b/Firmware/FFBoard/UserExtensions/Src/CanBridge.cpp @@ -12,8 +12,6 @@ #include "ledEffects.h" #include "cdc_device.h" -extern TIM_TypeDef TIM_MICROS; - ClassIdentifier CanBridge::info = { .name = "CAN Bridge (GVRET)" , .id=CLSID_MAIN_CAN, @@ -63,9 +61,9 @@ void CanBridge::sendMessage(uint32_t id, uint64_t msg,uint8_t len = 8,bool rtr = txHeader.id = id; txHeader.length = len; txHeader.rtr = rtr; - if(id & 1 << 31){ + if(id & 0x80000000){ txHeader.extId = true; - id &= 0x7FFFFFFF; + txHeader.id &= 0x7FFFFFFF; }else{ txHeader.extId = false; } @@ -102,10 +100,9 @@ void CanBridge::update(){ CAN_msg_header_rx rxHeader = msg.header; uint32_t time = rxHeader.timestamp; uint32_t id = rxHeader.id; -// if(rxHeader.ExtId != 0){ -// id = rxHeader.ExtId; -// id |= 0x80000000; -// } + if(rxHeader.extId){ + id |= 0x80000000; + } std::vector reply = { 0xF1,0,(char)(time & 0xff), (char)((time >> 8) & 0xff), (char)((time >> 16) & 0xff), (char)((time >> 24) & 0xff), (char)(id & 0xff), (char)((id >> 8) & 0xff), (char)((id >> 16) & 0xff), (char)((id >> 24) & 0xff), diff --git a/Firmware/FFBoard/UserExtensions/Src/EncoderBissC.cpp b/Firmware/FFBoard/UserExtensions/Src/EncoderBissC.cpp index 218e3e03a..5f36b13b1 100644 --- a/Firmware/FFBoard/UserExtensions/Src/EncoderBissC.cpp +++ b/Firmware/FFBoard/UserExtensions/Src/EncoderBissC.cpp @@ -101,16 +101,16 @@ void EncoderBissC::configSPI() { uint32_t prescale; switch (spiSpeed) { case 1 : - prescale = SPI_BAUDRATEPRESCALER_64; + prescale = spiPort.getClosestPrescaler(600000).first; break; case 2 : - prescale = SPI_BAUDRATEPRESCALER_32; + prescale = spiPort.getClosestPrescaler(1300000).first; break; case 3 : - prescale = SPI_BAUDRATEPRESCALER_16; + prescale = spiPort.getClosestPrescaler(2600000).first; break; default : - prescale = SPI_BAUDRATEPRESCALER_16; + prescale = spiPort.getClosestPrescaler(2600000).first; break; } diff --git a/Firmware/FFBoard/UserExtensions/Src/FFBHIDMain.cpp b/Firmware/FFBoard/UserExtensions/Src/FFBHIDMain.cpp index 3fd91228c..4bfa04554 100644 --- a/Firmware/FFBoard/UserExtensions/Src/FFBHIDMain.cpp +++ b/Firmware/FFBoard/UserExtensions/Src/FFBHIDMain.cpp @@ -2,7 +2,7 @@ * FFBWheel.cpp * * Created on: 31.01.2020 - * Author: Yannick / Lidders + * Author: Yannick / Lidders / Vincent */ #include @@ -14,18 +14,32 @@ #include "cmsis_os.h" extern osThreadId_t defaultTaskHandle; +#ifdef TIM_FFB +extern TIM_HandleTypeDef TIM_FFB; +#endif + +#ifndef OVERRIDE_FFBRATES +const FFBHIDMain::FFB_update_rates FFBHIDMain::ffbrates; // Default rates +#endif + ////////////////////////////////////////////// /** * setFFBEffectsCalc must be called in constructor of derived class to finish the setup */ -FFBHIDMain::FFBHIDMain(uint8_t axisCount) : - Thread("FFBMAIN", 256, 30), +FFBHIDMain::FFBHIDMain(uint8_t axisCount,bool hidAxis32b) : + Thread("FFBMAIN", 312, 30), SelectableInputs(ButtonSource::all_buttonsources,AnalogSource::all_analogsources), - axisCount(axisCount) + axisCount(axisCount),hidAxis32b(hidAxis32b) { - + if(hidAxis32b){ + reportHID = std::make_unique>(); + }else{ + reportHID = std::make_unique>(); + } +// reportHID((hidAxis32b ? HID_GamepadReport() : HID_GamepadReport())), +// lastReportHID((hidAxis32b ? HID_GamepadReport() : HID_GamepadReport())), restoreFlashDelayed(); // Load parameters registerCommands(); @@ -76,7 +90,7 @@ void FFBHIDMain::saveFlash(){ Flash_Write(ADR_FFBWHEEL_ANALOGCONF,this->ainsources); uint8_t conf1 = 0; - conf1 |= usb_report_rate_idx & 0x3; + conf1 |= usb_report_rate_idx & 0x7; Flash_Write(ADR_FFBWHEEL_CONF1,conf1); } @@ -90,9 +104,19 @@ void FFBHIDMain::Run(){ // control.emergency = true; // Immediately enter emergency state but without notifying other classes yet lastEstop = HAL_GetTick(); } +#endif +#ifdef TIM_FFB + HAL_TIM_Base_Start_IT(&TIM_FFB); // Start generating updates #endif while(true){ - Delay(1); +#ifndef TIM_FFB + while(ffb_rate_counter++ <= ffb_rate_divider){ + Delay(1); + } + ffb_rate_counter = 0; +#else + WaitForNotification(); +#endif updateControl(); } } @@ -154,12 +178,11 @@ void FFBHIDMain::send_report(){ // if(!sourcesSem.Take(10)){ // return; // } - // Read buttons - reportHID.buttons = 0; // Reset buttons + // Read buttons uint64_t b = 0; SelectableInputs::getButtonValues(b); - reportHID.buttons = b; + reportHID->setButtons(b); // Encoder //axes_manager->addAxesToReport(analogAxesReport, &count); @@ -167,7 +190,13 @@ void FFBHIDMain::send_report(){ std::vector* axes = axes_manager->getAxisValues(); uint8_t count = 0; for(auto val : *axes){ - setHidReportAxis(&reportHID,count++,val); + if(!hidAxis32b){ + val = val >> 16; // Scale to 16b + }else{ + val = val >> (32-HIDAXISRES_32B_BITS); // Scale if less than 32b + } + //setHidReportAxis(&reportHID,count++,val); + reportHID->setHidReportAxis(count++, val); } // Fill remaining values with analog inputs @@ -175,61 +204,99 @@ void FFBHIDMain::send_report(){ for(int32_t val : *axes){ if(count >= analogAxisCount) break; - setHidReportAxis(&reportHID,count++,val); + if((count < MAX_AXIS) && hidAxis32b) + val = val << (HIDAXISRES_32B_BITS-16); // Shift up 16 bit to fill 32b value. Primary axis is 32b + reportHID->setHidReportAxis(count++, val); } + // sourcesSem.Give(); // Fill rest for(;countsetHidReportAxis(count, 0); } /* * Only send a new report if actually changed since last time or timeout and hid is ready */ - if( (reportSendCounter > 100/usb_report_rate || (memcmp(&lastReportHID,&reportHID,sizeof(reportHID_t)) != 0) )) + if( (reportSendCounter > 100/usb_report_rate || reportHID->changed()) ) { - - - tud_hid_report(0, reinterpret_cast(&reportHID), sizeof(reportHID_t)); - lastReportHID = reportHID; - reportSendCounter = 0; - + tud_hid_report(0, reportHID->getBuffer(), reportHID->getLength()); + reportHID->swap(); // Report has changed and was sent. Swap buffers. + reportSendCounter = 0; } } +/** + * Returns current FFB update loop frequency in Hz + */ +float FFBHIDMain::getCurFFBFreq(){ + return ffbrates.basefreq/((uint32_t)ffbrates.dividers[usb_report_rate_idx].basediv); +} + /** * Changes the hid report rate based on the index for usb_report_rates */ void FFBHIDMain::setReportRate(uint8_t rateidx){ - rateidx = clip(rateidx, 0,sizeof(usb_report_rates)); + uint32_t usbrate_base = TUD_OPT_HIGH_SPEED ? 8000 : 1000; + if(tud_connected()){ // Get either actual rate or max supported rate if not connected + usbrate_base = tud_speed_get() == TUSB_SPEED_HIGH ? 8000 : 1000; // Only FS and HS supported + } + + rateidx = clip(rateidx, 0,ffbrates.dividers.size()); usb_report_rate_idx = rateidx; - usb_report_rate = usb_report_rates[rateidx]*HID_BINTERVAL; + + + // Either limit using rate counter or HW timer if present. +#ifdef TIM_FFB + TIM_FFB.Instance->ARR = ((1000000*(uint32_t)ffbrates.dividers[rateidx].basediv)/ffbrates.basefreq); // Assumes 1µs timer steps +#else + ffb_rate_divider = ffbrates.dividers[rateidx].basediv; +#endif + usb_report_rate = ffbrates.dividers[rateidx].hiddiv*HID_BINTERVAL; + // Divide report rate down if above actual usb rate + while(((ffbrates.basefreq / (uint32_t)ffbrates.dividers[rateidx].basediv) / usb_report_rate) > usbrate_base){ + usb_report_rate++; + } + + // Pass updated rate to other classes to update filters + float newRate = getCurFFBFreq(); + if(ffb) + ffb->updateSamplerate(newRate); + if(axes_manager) + axes_manager->updateSamplerate(newRate); } /** * Generates the speed strings to display to the user */ std::string FFBHIDMain::usb_report_rates_names() { - std::string s = ""; - for(uint8_t i = 0 ; i < sizeof(usb_report_rates);i++){ - s += std::to_string(1000/(HID_BINTERVAL*usb_report_rates[i])) + "Hz:"+std::to_string(i); - if(i < sizeof(usb_report_rates)-1) - s += ","; + std::string s = ""; + uint32_t usbrate_base = TUD_OPT_HIGH_SPEED ? 8000 : 1000; + if(tud_connected()){ // Get either actual rate or max supported rate if not connected + usbrate_base = tud_speed_get() == TUSB_SPEED_HIGH ? 8000 : 1000; // Only FS and HS supported + } + for(uint8_t i = 0 ; i < ffbrates.dividers.size();i++){ + uint32_t updatefreq = ffbrates.basefreq/((uint32_t)ffbrates.dividers[i].basediv); + uint32_t hidrate = (HID_BINTERVAL*ffbrates.dividers[i].hiddiv); + while((updatefreq/hidrate) > usbrate_base){ // Fall back if usb rate is still higher than supported + hidrate++; } - return s; + uint32_t hidfreq = updatefreq/hidrate; + s += "FFB "+std::to_string(updatefreq) + "Hz\nUSB " + std::to_string(hidfreq) + "Hz:"+std::to_string(i); + if(i < ffbrates.dividers.size()-1) + s += ","; } + return s; +} void FFBHIDMain::emergencyStop(bool reset){ control.emergency = !reset; axes_manager->emergencyStop(reset); } -//void FFBHIDMain::timerElapsed(TIM_HandleTypeDef* htim){ -// -//} - /** * USB unplugged @@ -253,6 +320,7 @@ void FFBHIDMain::usbResume(){ control.emergency = false; } #endif + setReportRate(this->usb_report_rate_idx); control.usb_disabled = false; axes_manager->usbResume(); } @@ -301,3 +369,11 @@ void FFBHIDMain::errorCallback(const Error &error, bool cleared){ } } +#ifdef TIM_FFB +void FFBHIDMain::timerElapsed(TIM_HandleTypeDef* htim){ + if(htim == &TIM_FFB){ + NotifyFromISR(); + } +} +#endif + diff --git a/Firmware/FFBoard/UserExtensions/Src/FFBWheel.cpp b/Firmware/FFBoard/UserExtensions/Src/FFBWheel.cpp index b77f5c37d..1e94dd4cc 100644 --- a/Firmware/FFBoard/UserExtensions/Src/FFBWheel.cpp +++ b/Firmware/FFBoard/UserExtensions/Src/FFBWheel.cpp @@ -24,7 +24,7 @@ const ClassIdentifier FFBWheel::getInfo(){ FFBWheel::FFBWheel() : - FFBHIDMain(1) + FFBHIDMain(1,FFBWHEEL_32B_MODE) { FFBHIDMain::setFFBEffectsCalc(ffb, effects_calc); } @@ -34,17 +34,29 @@ FFBWheel::~FFBWheel() { } - void FFBWheel::usbInit(){ +#ifdef HIDAXISRES_USE_32B_DESC #ifdef FFBWHEEL_USE_1AXIS_DESC - this->usbdev = std::make_unique(&usb_devdesc_ffboard_composite,usb_cdc_hid_conf_1axis,&usb_ffboard_strings_default); - FFBHIDMain::UsbHidHandler::setHidDesc(hid_1ffb_desc); - static_cast(ffb.get())->setDirectionEnableMask(0x02); +const uint8_t* usbconf = usb_cdc_hid_conf_1axis_32b; +const uint8_t* ffbdesc = hid_1ffb_desc_32b; #else - this->usbdev = std::make_unique(&usb_devdesc_ffboard_composite,usb_cdc_hid_conf_2axis,&usb_ffboard_strings_default); - FFBHIDMain::UsbHidHandler::setHidDesc(hid_2ffb_desc); - static_cast(ffb.get())->setDirectionEnableMask(0x04); +const uint8_t* ffbdesc = hid_2ffb_desc_32b; +const uint8_t* usbconf = usb_cdc_hid_conf_2axis_32b; +#endif +#else // ELSE 32B +#ifdef FFBWHEEL_USE_1AXIS_DESC +const uint8_t* usbconf = usb_cdc_hid_conf_1axis; +const uint8_t* ffbdesc = hid_1ffb_desc; +#else +const uint8_t* ffbdesc = hid_2ffb_desc; +const uint8_t* usbconf = usb_cdc_hid_conf_2axis; #endif +#endif + + this->usbdev = std::make_unique(&usb_devdesc_ffboard_composite,usbconf,&usb_ffboard_strings_default); + + FFBHIDMain::UsbHidHandler::setHidDesc(ffbdesc); + static_cast(ffb.get())->setDirectionEnableMask(0x04); usbdev->registerUsb(); } diff --git a/Firmware/FFBoard/UserExtensions/Src/FFBoardMain.cpp b/Firmware/FFBoard/UserExtensions/Src/FFBoardMain.cpp index da0b8da10..a3c9b559f 100644 --- a/Firmware/FFBoard/UserExtensions/Src/FFBoardMain.cpp +++ b/Firmware/FFBoard/UserExtensions/Src/FFBoardMain.cpp @@ -2,7 +2,7 @@ * FFBoardMain.cpp * * Created on: 23.01.2020 - * Author: Yannick + * Author: Yannick, Vincent */ #include "FFBoardMain.h" @@ -14,7 +14,7 @@ ClassIdentifier FFBoardMain::info ={.name = "Basic (Failsafe)" ,.id=0}; -char FFBoardMain::cdcbuf[64]; +char FFBoardMain::cdcbuf[(TUD_OPT_HIGH_SPEED ? 512 : 64)]; diff --git a/Firmware/FFBoard/UserExtensions/Src/TMC4671.cpp b/Firmware/FFBoard/UserExtensions/Src/TMC4671.cpp index 3b331632a..22ccd465c 100644 --- a/Firmware/FFBoard/UserExtensions/Src/TMC4671.cpp +++ b/Firmware/FFBoard/UserExtensions/Src/TMC4671.cpp @@ -2,14 +2,13 @@ * TMC4671.cpp * * Created on: Feb 1, 2020 - * Author: Yannick + * Author: Yannick, Vincent */ #include "TMC4671.h" #ifdef TMC4671DRIVER #include "ledEffects.h" #include "voltagesense.h" -//#include "stm32f4xx_hal_spi.h" #include #include #include "ErrorHandler.h" @@ -46,9 +45,11 @@ ClassIdentifier TMC4671::info = { }; + TMC4671::TMC4671(SPIPort& spiport,OutputPin cspin,uint8_t address) : CommandHandler("tmc", CLSID_MOT_TMC0,address-1), SPIDevice{motor_spi,cspin},Thread("TMC", TMC_THREAD_MEM, TMC_THREAD_PRIO) { + this->drv_address = address; CommandHandler::setCommandsEnabled(false); setAddress(address); registerCommands(); @@ -59,7 +60,7 @@ TMC4671::TMC4671(SPIPort& spiport,OutputPin cspin,uint8_t address) : spiConfig.peripheral.CLKPolarity = SPI_POLARITY_HIGH; spiConfig.peripheral.CLKPhase = SPI_PHASE_2EDGE; spiConfig.peripheral.NSS = SPI_NSS_SOFT; - spiConfig.peripheral.BaudRatePrescaler = spiPort.getClosestPrescaler(10e6).first; // 10MHz + spiConfig.peripheral.BaudRatePrescaler = spiPort.getClosestPrescaler(8e6,0,10e6).first; // 8 target, 10MHz max spiConfig.peripheral.FirstBit = SPI_FIRSTBIT_MSB; spiConfig.peripheral.TIMode = SPI_TIMODE_DISABLE; spiConfig.peripheral.CRCCalculation = SPI_CRCCALCULATION_DISABLE; @@ -180,6 +181,9 @@ void TMC4671::restoreFlash(){ if(Flash_Read(flashAddrs.encA, &miscval)){ restoreEncHallMisc(miscval); encHallRestored = true; + }else{ + // set first hwconf if we can't restore + this->setHwType(TMC4671::tmc4671_hw_configs[0].hwVersion); } uint16_t filterval; if(Flash_Read(flashAddrs.torqueFilter, &filterval)){ @@ -236,6 +240,18 @@ int32_t TMC4671::getTmcVM(){ return ((float)agpiA_VM * conf.hwconf.vmScaler) * 1000; } +void TMC4671::setupDriver() { + // Configuration specific to TMC4671 upon starting the motor + // The power limit is set by the Axis class via setPowerLimit during initialization. + + this->setExternalEncoderAllowed(true); + this->restoreFlash(); + this->setLimits(curLimits); + + // Start driver + this->setMotionMode(MotionMode::torque); + this->Start(); // Start thread +} /** * Sets all parameters of the driver at startup. Only has to be called once when the driver is detected @@ -261,7 +277,7 @@ bool TMC4671::initialize(){ */ pulseClipLed(); - this->spiConfig.peripheral.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_64; + this->spiConfig.peripheral.BaudRatePrescaler = spiPort.getClosestPrescaler(1e6).first; // 1MHz target spiPort.configurePort(&this->spiConfig.peripheral); ES_TMCdetected = true; } @@ -347,7 +363,7 @@ bool TMC4671::initialize(){ * Not calibrated perfectly! */ float TMC4671::getTemp(){ - if(!this->conf.hwconf.temperatureEnabled){ + if(!this->conf.hwconf.thermistorSettings.temperatureEnabled){ return 0; } TMC4671HardwareTypeConf* hwconf = &conf.hwconf; @@ -358,10 +374,10 @@ float TMC4671::getTemp(){ if(adcval <= 0){ return 0.0; } - float r = hwconf->thermistor_R2 * (((float)43252 / (float)adcval)); //43252 equivalent ADC count if it was 3.3V and not 2.5V + float r = hwconf->thermistorSettings.thermistor_R2 * (((float)43252 / (float)adcval)); //43252 equivalent ADC count if it was 3.3V and not 2.5V // Beta - r = (1.0 / 298.15) + log(r / hwconf->thermistor_R) / hwconf->thermistor_Beta; + r = (1.0 / 298.15) + log(r / hwconf->thermistorSettings.thermistor_R) / hwconf->thermistorSettings.thermistor_Beta; r = 1.0 / r; r -= 273.15; return r; @@ -549,9 +565,9 @@ void TMC4671::Run(){ } // Temperature sense - if(conf.hwconf.temperatureEnabled){ + if(conf.hwconf.thermistorSettings.temperatureEnabled){ float temp = getTemp(); - if(temp > conf.hwconf.temp_limit){ + if(temp > conf.hwconf.thermistorSettings.temp_limit){ changeState(TMC_ControlState::OverTemp); pulseErrLed(); } @@ -577,12 +593,12 @@ void TMC4671::Run(){ break; case TMC_ControlState::EncoderInit: - if(powerInitialized && hasPower()) + if(powerInitialized && hasPower() && conf.motconf.motor_type != MotorType::NONE) encoderInit(); break; case TMC_ControlState::ExternalEncoderInit: - if(powerInitialized && hasPower() && drvEncoder != nullptr) + if(powerInitialized && hasPower() && drvEncoder != nullptr && conf.motconf.motor_type != MotorType::NONE) encoderInit(); break; @@ -651,7 +667,9 @@ void TMC4671::calibrateEncoder(){ // Report changes CommandHandler::broadcastCommandReply(CommandReply(abnconf.npol ? 1 : 0), (uint32_t)TMC4671_commands::encpol, CMDtype::get); }else if(conf.motconf.enctype == EncoderType_TMC::sincos || conf.motconf.enctype == EncoderType_TMC::uvw){ - calibrateAenc(); + if(!conf.hwconf.flags.analog_enc_skip_cal){ + calibrateAenc(); + } }else if(conf.motconf.enctype == EncoderType_TMC::ext){ estimateExtEnc(); } @@ -724,7 +742,7 @@ bool TMC4671::pidAutoTune(){ flux = getActualFlux(); } - if(peakflux > (targetflux + ( targetflux * 0.03))) // Overshoot target by 3% + if(peakflux > (targetflux + ( targetflux * TMC4671_ITUNE_CUTOFF))) // Overshoot target by 4% default { fluxI -= step_i; // Revert last step break; @@ -1165,8 +1183,8 @@ int16_t TMC4671::getPhiE_Enc(){ * Steps the motor a few times to check if the encoder follows correctly */ bool TMC4671::checkEncoder(){ - if(this->conf.motconf.motor_type != MotorType::STEPPER && this->conf.motconf.motor_type != MotorType::BLDC && - conf.motconf.enctype != EncoderType_TMC::uvw && conf.motconf.enctype != EncoderType_TMC::sincos && conf.motconf.enctype != EncoderType_TMC::abn && conf.motconf.enctype != EncoderType_TMC::ext) + if((this->conf.motconf.motor_type != MotorType::STEPPER && this->conf.motconf.motor_type != MotorType::BLDC) || ( + conf.motconf.enctype != EncoderType_TMC::uvw && conf.motconf.enctype != EncoderType_TMC::sincos && conf.motconf.enctype != EncoderType_TMC::abn && conf.motconf.enctype != EncoderType_TMC::ext)) { // If not stepper or bldc return return true; } @@ -1362,8 +1380,8 @@ bool TMC4671::calibrateAdcOffset(uint16_t time){ uint32_t measurements_idle = 0; uint64_t totalA=0; uint64_t totalB=0; - bool allowTemp = conf.hwconf.temperatureEnabled; - conf.hwconf.temperatureEnabled = false; // Temp check interrupts adc + bool allowTemp = conf.hwconf.thermistorSettings.temperatureEnabled; + conf.hwconf.thermistorSettings.temperatureEnabled = false; // Temp check interrupts adc writeReg(0x03, 0); // Read raw adc PhiE lastphie = getPhiEtype(); MotionMode lastmode = getMotionMode(); @@ -1402,7 +1420,7 @@ bool TMC4671::calibrateAdcOffset(uint16_t time){ // setPwm(TMC_PwmMode::off); //Disable pwm // this->changeState(TMC_ControlState::HardError); adcCalibrated = false; - conf.hwconf.temperatureEnabled = allowTemp; + conf.hwconf.thermistorSettings.temperatureEnabled = allowTemp; return false; // An adc or shunt amp is likely broken. do not proceed. } conf.adc_I0_offset = offsetAidle; @@ -1413,7 +1431,7 @@ bool TMC4671::calibrateAdcOffset(uint16_t time){ setPhiEtype(lastphie); setMotionMode(lastmode,true); adcCalibrated = true; - conf.hwconf.temperatureEnabled = allowTemp; + conf.hwconf.thermistorSettings.temperatureEnabled = allowTemp; return true; } @@ -1447,7 +1465,9 @@ void TMC4671::encoderInit(){ setPosSel(PosSelection::PhiM_aenc); // Mechanical Angle setVelSel(VelSelection::PhiM_aenc); // Mechanical Angle (RPM) //setup_AENC(aencconf); - calibrateAenc(); + if(!conf.hwconf.flags.analog_enc_skip_cal){ + calibrateAenc(); + } } // find index @@ -1512,9 +1532,10 @@ void TMC4671::encoderInit(){ */ void TMC4671::setEncoderType(EncoderType_TMC type){ // If no external timer is set external encoder is not valid - if((!externalEncoderTimer || !externalEncoderAllowed()) && type == EncoderType_TMC::ext){ + if( !conf.hwconf.isEncSupported(type) || ((!externalEncoderTimer || !externalEncoderAllowed()) && type == EncoderType_TMC::ext)){ type = EncoderType_TMC::NONE; } + this->conf.motconf.enctype = type; this->statusMask.flags.AENC_N = 0; this->statusMask.flags.ENC_N = 0; @@ -1848,7 +1869,9 @@ Encoder* TMC4671::getEncoder(){ void TMC4671::setEncoder(std::shared_ptr& encoder){ MotorDriver::drvEncoder = encoder; if(conf.motconf.enctype == EncoderType_TMC::ext && externalEncoderTimer){ - // TODO Calibrate and align external encoder + if(!extEncUpdater){ // If updater has not been set up because the encoder mode was changed before the external encoder passed force it now + setUpExtEncTimer(); + } changeState(TMC_ControlState::ExternalEncoderInit); } } @@ -2007,14 +2030,19 @@ bool TMC4671::externalEncoderAllowed(){ #ifndef TIM_TMC return false; #else - return allowExternalEncoder; + return allowExternalEncoder && conf.hwconf.flags.enc_ext; #endif } void TMC4671::setMotorType(MotorType motor,uint16_t poles){ + + if(!conf.hwconf.isMotSupported(motor)){ + motor = MotorType::NONE; + } if(motor == MotorType::DC){ poles = 1; } + conf.motconf.motor_type = motor; conf.motconf.pole_pairs = poles; uint32_t mtype = poles | ( ((uint8_t)motor&0xff) << 16); @@ -2031,8 +2059,11 @@ void TMC4671::setTorque(int16_t torque){ if(curMotionMode != MotionMode::torque){ setMotionMode(MotionMode::torque,true); } - updateReg(0x64,torque,0xffff,16); + + // Update main torque setpoint + updateReg(0x64, torque, 0xffff, 16); } + int16_t TMC4671::getTorque(){ return readReg(0x64) >> 16; } @@ -2050,7 +2081,17 @@ void TMC4671::setFluxTorque(int16_t flux, int16_t torque){ if(curMotionMode != MotionMode::torque && !emergency){ setMotionMode(MotionMode::torque,true); } +#ifdef TMC4671_TORQUE_USE_ASYNC + writeRegAsync(0x64, (flux & 0xffff) | (torque << 16)); +#else + // Update main flux and torque setpoints writeReg(0x64, (flux & 0xffff) | (torque << 16)); +#endif +} + +int16_t TMC4671::getVelocityControllerTorque(){ + writeReg(0x6F, 4); // INTERIM_ADDR = 4 for PIDOUT_TARGET_TORQUE + return (int16_t)readReg(0x6E); // Read from INTERIM_DATA } void TMC4671::setFluxTorqueFF(int16_t flux, int16_t torque){ @@ -2104,6 +2145,11 @@ void TMC4671::setUqUdLimit(uint16_t limit){ writeReg(0x5D, limit); } +void TMC4671::setPowerLimit(uint16_t power) { + maxPowerAxis = power; + setTorqueLimit(power); +} + void TMC4671::setTorqueLimit(uint16_t limit){ this->curLimits.pid_torque_flux = limit; bangInitPower = (float)limit*0.75; @@ -2262,7 +2308,7 @@ void TMC4671::setTorqueFilter(TMC4671Biquad_conf& conf){ /** * Sets the raw brake resistor limits. * Centered at 0x7fff - * Set both 0 to deactivate + * Set both 0xffff to deactivate */ void TMC4671::setBrakeLimits(uint16_t low,uint16_t high){ uint32_t val = low | (high << 16); @@ -2682,161 +2728,47 @@ void TMC4671::restoreEncHallMisc(uint16_t val){ this->hallconf.interpolation = (val>>9) & 0x01; this->curPids.sequentialPI = (val>>10) & 0x01; - setHwType((TMC_HW_Ver)((val >> 11) & 0x1F)); + setHwType((uint8_t)((val >> 11) & 0x1F)); } + + /** * Sets some constants and features depending on the hardware version of the driver */ -void TMC4671::setHwType(TMC_HW_Ver type){ - //TMC4671HardwareTypeConf newHwConf; - switch(type){ - case TMC_HW_Ver::v1_3_66mv: - { - TMC4671HardwareTypeConf newHwConf = { - .hwVersion = TMC_HW_Ver::v1_3_66mv, - .adcOffset = 0, - .thermistor_R2 = 1500, - .thermistor_R = 10000, - .thermistor_Beta = 4300, - .temperatureEnabled = true, - .temp_limit = 90, - .currentScaler = 2.5 / (0x7fff * 0.066), // sensor 66mV/A - .brakeLimLow = 50700, - .brakeLimHigh = 50900, - .vmScaler = (2.5 / 0x7fff) * ((1.5+71.5)/1.5), - .vSenseMult = VOLTAGE_MULT_DEFAULT, - .bbm = 50 // DMTH8003SPS need longer deadtime - }; - this->conf.hwconf = newHwConf; - break; - } - case TMC_HW_Ver::v1_2_2_100mv: - { - TMC4671HardwareTypeConf newHwConf = { - .hwVersion = TMC_HW_Ver::v1_2_2_100mv, - .adcOffset = 0, - .thermistor_R2 = 1500, - .thermistor_R = 10000, - .thermistor_Beta = 4300, - .temperatureEnabled = true, - .temp_limit = 90, - .currentScaler = 2.5 / (0x7fff * 0.1), // w. TMCS1100A2 sensor 100mV/A - .brakeLimLow = 50700, - .brakeLimHigh = 50900, - .vmScaler = (2.5 / 0x7fff) * ((1.5+71.5)/1.5), - .vSenseMult = VOLTAGE_MULT_DEFAULT, - .bbm = 40 - }; - this->conf.hwconf = newHwConf; - break; - } - case TMC_HW_Ver::v1_2_2_LEM20: - { - // TODO possibly lower PWM limit because of lower valid sensor range - TMC4671HardwareTypeConf newHwConf = { - .hwVersion = TMC_HW_Ver::v1_2_2, - .adcOffset = 0, - .thermistor_R2 = 1500, - .thermistor_R = 10000, - .thermistor_Beta = 4300, - .temperatureEnabled = true, - .temp_limit = 90, - .currentScaler = 2.5 / (0x7fff * 0.04), // w. LEM 20 sensor 40mV/A - .brakeLimLow = 50700, - .brakeLimHigh = 50900, - .vmScaler = (2.5 / 0x7fff) * ((1.5+71.5)/1.5), - .vSenseMult = VOLTAGE_MULT_DEFAULT, - .bbm = 20 - }; - this->conf.hwconf = newHwConf; - break; - } - case TMC_HW_Ver::v1_2_2: - { - // TODO possibly lower PWM limit because of lower valid sensor range - TMC4671HardwareTypeConf newHwConf = { - .hwVersion = TMC_HW_Ver::v1_2_2, - .adcOffset = 0, - .thermistor_R2 = 1500, - .thermistor_R = 10000, - .thermistor_Beta = 4300, - .temperatureEnabled = true, - .temp_limit = 90, - .currentScaler = 2.5 / (0x7fff * 0.08), // w. LEM 10 sensor 80mV/A - .brakeLimLow = 50700, - .brakeLimHigh = 50900, - .vmScaler = (2.5 / 0x7fff) * ((1.5+71.5)/1.5), - .vSenseMult = VOLTAGE_MULT_DEFAULT, - .bbm = 20 - }; - this->conf.hwconf = newHwConf; - break; - } - - case TMC_HW_Ver::v1_2: - { - TMC4671HardwareTypeConf newHwConf = { - .hwVersion = TMC_HW_Ver::v1_2, - .adcOffset = 1000, - .thermistor_R2 = 1500, - .thermistor_R = 22000, - .thermistor_Beta = 4300, - .temperatureEnabled = true, - .temp_limit = 90, - .currentScaler = 2.5 / (0x7fff * 60.0 * 0.0015), // w. 60x 1.5mOhm sensor - .brakeLimLow = 50700, - .brakeLimHigh = 50900, - .vmScaler = (2.5 / 0x7fff) * ((1.5+71.5)/1.5), - .vSenseMult = VOLTAGE_MULT_DEFAULT, - .bbm = 20 - }; - this->conf.hwconf = newHwConf; - // Activates around 60V as last resort failsave. Check offsets from tmc leakage. ~ 1.426V - break; - } - - - case TMC_HW_Ver::v1_0: - { - TMC4671HardwareTypeConf newHwConf = { - .hwVersion = TMC_HW_Ver::v1_0, - .adcOffset = 1000, - .thermistor_R2 = 0, - .thermistor_R = 0, - .thermistor_Beta = 0, - .temperatureEnabled = false, - .temp_limit = 90, - .currentScaler = 2.5 / (0x7fff * 60.0 * 0.0015), // w. 60x 1.5mOhm sensor - .brakeLimLow = 52400, - .brakeLimHigh = 52800, - .vmScaler = (2.5 / 0x7fff) * ((1.5+71.5)/1.5), - .vSenseMult = VOLTAGE_MULT_DEFAULT, - .bbm = 20 - }; - this->conf.hwconf = newHwConf; - - break; +void TMC4671::setHwType(uint8_t type){ + // If only one config is valid use this regardless of requested type + if(TMC4671::tmc4671_hw_configs.size() == 1){ + this->conf.hwconf = TMC4671::tmc4671_hw_configs[0]; + }else{ // Search for config matching requested type + for(const TMC4671HardwareTypeConf& newConf : TMC4671::tmc4671_hw_configs){ + if(type == newConf.hwVersion){ + this->conf.hwconf = newConf; + break; + } + } } - case TMC_HW_Ver::NONE: - { - default: - TMC4671HardwareTypeConf newHwConf; - newHwConf.temperatureEnabled = false; - newHwConf.hwVersion = TMC_HW_Ver::NONE; - newHwConf.currentScaler = 0; - this->conf.hwconf = newHwConf; - setBrakeLimits(0,0); // Disables internal brake resistor activation. DANGER! - break; - } - } setVSenseMult(this->conf.hwconf.vSenseMult); // Update vsense multiplier //setupBrakePin(vdiffAct, vdiffDeact, vMax); // TODO if required setBrakeLimits(this->conf.hwconf.brakeLimLow,this->conf.hwconf.brakeLimHigh); setBBM(this->conf.hwconf.bbm,this->conf.hwconf.bbm); + // Force changing motor and encoder types to prevent invalid types being selected if new hw type does not support them + setMotorType(this->conf.motconf.motor_type, this->conf.motconf.pole_pairs); + setEncoderType(this->conf.motconf.enctype); +} +/** + * Appends a formatted reply with currently available hardware version configs + */ +void TMC4671::replyHardwareVersions(const std::span& versions,std::vector& replies){ +// uint8_t idx = 0; + for(const TMC4671HardwareTypeConf& c : versions){ + if(this->canChangeHwType || c.hwVersion == this->conf.hwconf.hwVersion){ + replies.emplace_back( std::to_string((uint8_t)c.hwVersion) + ":" + c.name,(uint8_t)c.hwVersion); + } + } } void TMC4671::registerCommands(){ @@ -2923,10 +2855,16 @@ CommandStatus TMC4671::command(const ParsedCommand& cmd,std::vectorconf.motconf.motor_type); - }else if(cmd.type == CMDtype::set && (uint8_t)cmd.type < (uint8_t)MotorType::ERR){ + }else if(cmd.type == CMDtype::set && (uint8_t)cmd.type <= (uint8_t)MotorType::BLDC){ this->setMotorType((MotorType)cmd.val, this->conf.motconf.pole_pairs); }else{ - replies.emplace_back("NONE=0,DC=1,2Ph Stepper=2,3Ph BLDC=3"); + std::string rplstr = ""; + TMC4671HardwareTypeConf::SupportedModes_s* confflags = &conf.hwconf.flags; + if(confflags->mot_none) rplstr += "NONE=0,"; + if(confflags->mot_dc) rplstr += "DC=1,"; + if(confflags->mot_stepper) rplstr += "Stepper 2Ph=2,"; + if(confflags->mot_bldc) rplstr += "BLDC 3Ph=3"; + replies.emplace_back(rplstr); } break; @@ -2936,11 +2874,15 @@ CommandStatus TMC4671::command(const ParsedCommand& cmd,std::vectorsetEncoderType((EncoderType_TMC)cmd.val); }else{ - if(externalEncoderAllowed()) - replies.emplace_back("NONE=0,ABN=1,SinCos=2,Analog UVW=3,Hall=4,External=5"); - else - replies.emplace_back("NONE=0,ABN=1,SinCos=2,Analog UVW=3,Hall=4"); - + std::string rplstr = ""; + TMC4671HardwareTypeConf::SupportedModes_s* confflags = &conf.hwconf.flags; + if(confflags->enc_none) rplstr += "NONE=0,"; + if(confflags->enc_abn) rplstr += "ABN=1,"; + if(confflags->enc_sincos) rplstr += "SinCos=2,"; + if(confflags->enc_uvw) rplstr += "UVW=3,"; + if(confflags->enc_hall) rplstr += "HALL=4,"; + if(confflags->enc_ext && externalEncoderAllowed()) rplstr += "External=5"; + replies.emplace_back(rplstr); } break; @@ -2948,16 +2890,11 @@ CommandStatus TMC4671::command(const ParsedCommand& cmd,std::vector(this); // Setup timer this->externalEncoderTimer = &TIM_TMC; - this->externalEncoderTimer->Instance->ARR = 200; // 200 = 5khz = 5 tmc cycles, 250 = 4khz, 240 = 6 tmc cycles - this->externalEncoderTimer->Instance->PSC = (SystemCoreClock / 2000000)+1; // timer running at half clock speed. 1µs ticks + this->externalEncoderTimer->Instance->ARR = TIM_TMC_ARR; // 200 = 5khz = 5 tmc cycles, 250 = 4khz, 240 = 6 tmc cycles + this->externalEncoderTimer->Instance->PSC = ((TIM_TMC_BCLK)/1000000) +1; // 1µs ticks this->externalEncoderTimer->Instance->CR1 = 1; HAL_TIM_Base_Start_IT(this->externalEncoderTimer); #endif diff --git a/Firmware/FFBoard/UserExtensions/Src/TMC4671_configs.cpp b/Firmware/FFBoard/UserExtensions/Src/TMC4671_configs.cpp new file mode 100644 index 000000000..1d5cb0d0d --- /dev/null +++ b/Firmware/FFBoard/UserExtensions/Src/TMC4671_configs.cpp @@ -0,0 +1,117 @@ +/* + * TMC4671_configs.cpp + * + * Created on: Feb 20, 2024 + * Author: Yannick + */ + +#include "TMC4671.h" +#include "constants.h" +#include "span" + +#if !defined(TMC4671_OVERRIDE_HWCONFS) && defined(TMC4671DRIVER) +// Default configs for officially supported hardware + + +const TMC4671HardwareTypeConf conf1_0 = { + .name = "v1.0 AD8417 (1.5mOhm)", + .hwVersion = (uint8_t)TMC_HW_Ver::v1_0, + .adcOffset = 1000, + .thermistorSettings = { + .thermistor_R2 = 0, + .thermistor_R = 0, + .thermistor_Beta = 0, + .temp_limit = 90, + .temperatureEnabled = false, + }, + .currentScaler = 2.5 / (0x7fff * 60.0 * 0.0015), // w. 60x 1.5mOhm sensor + .brakeLimLow = 52400, + .brakeLimHigh = 52800, + .vmScaler = (2.5 / 0x7fff) * ((1.5+71.5)/1.5), + .vSenseMult = VOLTAGE_MULT_DEFAULT, + .clockfreq = 25e6, + .bbm = 20, +}; +const TMC4671HardwareTypeConf conf1_2 = { + .name = "v1.2 AD8417 (1.5mOhm)", + .hwVersion = (uint8_t)TMC_HW_Ver::v1_2, + .adcOffset = 1000, + .thermistorSettings = { + .thermistor_R2 = 1500, + .thermistor_R = 22000, + .thermistor_Beta = 4300, + .temp_limit = 90, + .temperatureEnabled = true, + }, + .currentScaler = 2.5 / (0x7fff * 60.0 * 0.0015), // w. 60x 1.5mOhm sensor + .brakeLimLow = 50700, + .brakeLimHigh = 50900, + .vmScaler = (2.5 / 0x7fff) * ((1.5+71.5)/1.5), + .vSenseMult = VOLTAGE_MULT_DEFAULT, + .clockfreq = 25e6, + .bbm = 20, +}; +const TMC4671HardwareTypeConf conf1_2_2 = { + .name = "v1.2.2 LEM 10 (80mV/A)", + .hwVersion = (uint8_t)TMC_HW_Ver::v1_2_2, + .adcOffset = 0, + .thermistorSettings = { + .thermistor_R2 = 1500, + .thermistor_R = 10000, + .thermistor_Beta = 4300, + .temp_limit = 90, + .temperatureEnabled = true, + }, + .currentScaler = 2.5 / (0x7fff * 0.08), // w. LEM 10 sensor 80mV/A + .brakeLimLow = 50700, + .brakeLimHigh = 50900, + .vmScaler = (2.5 / 0x7fff) * ((1.5+71.5)/1.5), + .vSenseMult = VOLTAGE_MULT_DEFAULT, + .clockfreq = 25e6, + .bbm = 20, +}; +const TMC4671HardwareTypeConf conf1_3 = { + .name = "v1.3 ACS724 (66mV/A)", + .hwVersion = (uint8_t)TMC_HW_Ver::v1_3_66mv, + .adcOffset = 0, + .thermistorSettings = { + .thermistor_R2 = 1500, + .thermistor_R = 10000, + .thermistor_Beta = 4300, + .temp_limit = 90, + .temperatureEnabled = true, + }, + .currentScaler = 2.5 / (0x7fff * 0.066), // sensor 66mV/A + .brakeLimLow = 50700, + .brakeLimHigh = 50900, + .vmScaler = (2.5 / 0x7fff) * ((1.5+71.5)/1.5), + .vSenseMult = VOLTAGE_MULT_DEFAULT, + .clockfreq = 25e6, + .bbm = 40, // May need longer deadtime + .flags{ + .mot_none = 1, + .mot_dc = 1, + .mot_bldc = 1, + .mot_stepper = 1, + + .enc_none = 1, + .enc_abn = 1, + .enc_sincos = 1, + .enc_uvw = 1, + .enc_hall = 1, + .enc_ext = 1, + + .allowFluxDissipationDeactivation = 1 + } +}; +const auto tmc4671_hw_configs_array = std::to_array({conf1_3,conf1_2_2,conf1_2,conf1_0}); +std::span TMC4671::tmc4671_hw_configs = tmc4671_hw_configs_array; +#endif + +// Only a single config with default settings. Some defaults can be overridden by defines +#ifdef TMC4671_CUSTOM_DEFAULT_HWCONF +const TMC4671HardwareTypeConf defaultconf; +const auto tmc4671_hw_configs_array = std::to_array({defaultconf}); +std::span TMC4671::tmc4671_hw_configs = tmc4671_hw_configs_array; + +#endif diff --git a/Firmware/FFBoard/UserExtensions/Src/eeprom_addresses.c b/Firmware/FFBoard/UserExtensions/Src/eeprom_addresses.c index d111d712a..2a0e83a21 100644 --- a/Firmware/FFBoard/UserExtensions/Src/eeprom_addresses.c +++ b/Firmware/FFBoard/UserExtensions/Src/eeprom_addresses.c @@ -70,6 +70,7 @@ const uint16_t VirtAddVarTab[NB_OF_VAR] = ADR_FFB_EFFECTS1, // 0-7 inertia, 8-15 friction ADR_FFB_EFFECTS2, // 0-7 spring, 8-15 damper ADR_FFB_EFFECTS3, // 0-7 friction ramp up zone, 8-9 filterProfile + ADR_FFB_RECONSTRUCTION_FILTER, // 0-1 recon filter mode // Button Sources: ADR_ADS111X_CONF1, // How many axis configured 1-3 @@ -80,6 +81,7 @@ const uint16_t VirtAddVarTab[NB_OF_VAR] = ADR_AXIS1_DEGREES, ADR_AXIS1_MAX_SPEED, // Store the max speed ADR_AXIS1_MAX_ACCEL, // Store the max accel + ADR_AXIS1_MAX_SLEWRATE_DRV, // Max slew rate for drv ADR_AXIS1_ENDSTOP, // 0-7 endstop margin, 8-15 endstop stiffness ADR_AXIS1_EFFECTS1, // 0-7 idlespring, 8-15 damper ADR_AXIS1_SPEEDACCEL_FILTER, // Speed/Accel filter Lowpass profile @@ -106,6 +108,7 @@ const uint16_t VirtAddVarTab[NB_OF_VAR] = ADR_AXIS2_DEGREES, ADR_AXIS2_MAX_SPEED, // Store the max speed ADR_AXIS2_MAX_ACCEL, // Store the max accel + ADR_AXIS2_MAX_SLEWRATE_DRV, // Max slew rate for drv ADR_AXIS2_ENDSTOP, // 0-7 endstop margin, 8-15 endstop stiffness ADR_AXIS2_EFFECTS1, // 0-7 idlespring, 8-15 damper ADR_AXIS2_SPEEDACCEL_FILTER, // Speed/Accel filter Lowpass profile @@ -132,6 +135,7 @@ const uint16_t VirtAddVarTab[NB_OF_VAR] = ADR_AXIS3_DEGREES, ADR_AXIS3_MAX_SPEED, // Store the max speed ADR_AXIS3_MAX_ACCEL, // Store the max accel + ADR_AXIS3_MAX_SLEWRATE_DRV, // Max slew rate for drv ADR_AXIS3_ENDSTOP, // 0-7 endstop margin, 8-15 endstop stiffness ADR_AXIS3_EFFECTS1, // 0-7 idlespring, 8-15 damper ADR_AXIS3_SPEEDACCEL_FILTER, // Speed/Accel filter Lowpass profile @@ -270,6 +274,7 @@ const uint16_t exportableFlashAddresses[NB_EXPORTABLE_ADR] = ADR_FFB_EFFECTS1, // 0-7 inertia, 8-15 friction ADR_FFB_EFFECTS2, // 0-7 spring, 8-15 damper ADR_FFB_EFFECTS3, // 0-7 friction ramp up zone, 8-9 filterProfile + ADR_FFB_RECONSTRUCTION_FILTER, // 0-1 recon filter mode // Button Sources: ADR_ADS111X_CONF1, // How many axis configured 1-3 @@ -280,6 +285,7 @@ const uint16_t exportableFlashAddresses[NB_EXPORTABLE_ADR] = ADR_AXIS1_DEGREES, ADR_AXIS1_MAX_SPEED, // Store the max speed ADR_AXIS1_MAX_ACCEL, // Store the max accel + ADR_AXIS1_MAX_SLEWRATE_DRV, // Max slew rate for drv ADR_AXIS1_ENDSTOP, // 0-7 endstop margin, 8-15 endstop stiffness ADR_AXIS1_EFFECTS1, // 0-7 idlespring, 8-15 damper ADR_AXIS1_SPEEDACCEL_FILTER, // Speed/Accel filter Lowpass profile @@ -306,6 +312,7 @@ const uint16_t exportableFlashAddresses[NB_EXPORTABLE_ADR] = ADR_AXIS2_DEGREES, ADR_AXIS2_MAX_SPEED, // Store the max speed ADR_AXIS2_MAX_ACCEL, // Store the max accel + ADR_AXIS2_MAX_SLEWRATE_DRV, // Max slew rate for drv ADR_AXIS2_ENDSTOP, // 0-7 endstop margin, 8-15 endstop stiffness ADR_AXIS2_EFFECTS1, // 0-7 idlespring, 8-15 damper ADR_AXIS2_SPEEDACCEL_FILTER, // Speed/Accel filter Lowpass profile @@ -332,6 +339,7 @@ const uint16_t exportableFlashAddresses[NB_EXPORTABLE_ADR] = ADR_AXIS3_DEGREES, ADR_AXIS3_MAX_SPEED, // Store the max speed ADR_AXIS3_MAX_ACCEL, // Store the max accel + ADR_AXIS3_MAX_SLEWRATE_DRV, // Max slew rate for drv ADR_AXIS3_ENDSTOP, // 0-7 endstop margin, 8-15 endstop stiffness ADR_AXIS3_EFFECTS1, // 0-7 idlespring, 8-15 damper ADR_AXIS3_SPEEDACCEL_FILTER, // Speed/Accel filter Lowpass profile diff --git a/Firmware/FFBoard/UserExtensions/Src/usb_descriptors.cpp b/Firmware/FFBoard/UserExtensions/Src/usb_descriptors.cpp index 442758d04..d199462e9 100644 --- a/Firmware/FFBoard/UserExtensions/Src/usb_descriptors.cpp +++ b/Firmware/FFBoard/UserExtensions/Src/usb_descriptors.cpp @@ -7,7 +7,6 @@ #include "tusb.h" #include "usb_descriptors.h" #include "usbd.h" -#include "stm32f4xx_hal.h" #include "main.h" #include "usb_hid_ffb_desc.h" @@ -48,62 +47,44 @@ const tusb_desc_device_t usb_devdesc_ffboard_composite = const uint8_t usb_cdc_conf[] = { // Config number, interface count, string index, total length, attribute, power in mA - TUD_CONFIG_DESCRIPTOR(1, 2, 0, (TUD_CONFIG_DESC_LEN + TUD_CDC_DESC_LEN), TUSB_DESC_CONFIG_ATT_REMOTE_WAKEUP, 100), + TUD_CONFIG_DESCRIPTOR(1, 2, 0, (TUD_CONFIG_DESC_LEN + TUD_CDC_DESC_LEN), TUSB_DESC_CONFIG_ATT_REMOTE_WAKEUP | TUSB_DESC_CONFIG_ATT_SELF_POWERED, 100), // 1st CDC: Interface number, string index, EP notification address and size, EP data address (out, in) and size. TUD_CDC_DESCRIPTOR(0, 4, 0x82, 8, 0x01, 0x81, 64), }; + // Composite CDC and HID #ifdef AXIS1_FFB_HID_DESC -const uint8_t usb_cdc_hid_conf_1axis[] = -{ - // Config number, interface count, string index, total length, attribute, power in mA - TUD_CONFIG_DESCRIPTOR(1, 3, 0, (TUD_CONFIG_DESC_LEN + TUD_CDC_DESC_LEN + TUD_HID_INOUT_DESC_LEN), TUSB_DESC_CONFIG_ATT_REMOTE_WAKEUP, 100), - - // 1st CDC: Interface number, string index, EP notification address and size, EP data address (out, in) and size. - TUD_CDC_DESCRIPTOR(0, 4, 0x82, 8, 0x01, 0x81, 64), + const uint8_t usb_cdc_hid_conf_1axis[] ={USB_CONF_DESC_HID_CDC(USB_HID_1FFB_REPORT_DESC_SIZE,64)}; +#endif - // HID Descriptor. EP 83 and 2 - TUD_HID_INOUT_DESCRIPTOR(2, 5, HID_ITF_PROTOCOL_NONE, USB_HID_1FFB_REPORT_DESC_SIZE, 0x83, 0x02, 64, HID_BINTERVAL), -}; +#ifdef AXIS1_FFB_HID_DESC_32B + const uint8_t usb_cdc_hid_conf_1axis_32b[] ={USB_CONF_DESC_HID_CDC(USB_HID_1FFB_REPORT_DESC_32B_SIZE,64)}; +#if TUD_OPT_HIGH_SPEED + const uint8_t usb_cdc_hid_conf_1axis_32b_hs[] ={USB_CONF_DESC_HID_CDC(USB_HID_1FFB_REPORT_DESC_32B_SIZE,512)}; +#endif #endif // Composite CDC and HID #ifdef AXIS2_FFB_HID_DESC -const uint8_t usb_cdc_hid_conf_2axis[] = -{ - // Config number, interface count, string index, total length, attribute, power in mA - TUD_CONFIG_DESCRIPTOR(1, 3, 0, (TUD_CONFIG_DESC_LEN + TUD_CDC_DESC_LEN + TUD_HID_INOUT_DESC_LEN), TUSB_DESC_CONFIG_ATT_REMOTE_WAKEUP, 100), - - // 1st CDC: Interface number, string index, EP notification address and size, EP data address (out, in) and size. - TUD_CDC_DESCRIPTOR(0, 4, 0x82, 8, 0x01, 0x81, 64), + const uint8_t usb_cdc_hid_conf_2axis[] ={USB_CONF_DESC_HID_CDC(USB_HID_2FFB_REPORT_DESC_SIZE,64)}; +#endif - // HID Descriptor. EP 83 and 2 - TUD_HID_INOUT_DESCRIPTOR(2, 5, HID_ITF_PROTOCOL_NONE, USB_HID_2FFB_REPORT_DESC_SIZE, 0x83, 0x02, 64, HID_BINTERVAL), -}; +#ifdef AXIS2_FFB_HID_DESC_32B + const uint8_t usb_cdc_hid_conf_2axis_32b[] ={USB_CONF_DESC_HID_CDC(USB_HID_2FFB_REPORT_DESC_32B_SIZE,64)}; #endif // Composite CDC and HID #ifdef FFB_HID_DESC_GAMEPAD -const uint8_t usb_cdc_hid_conf_gamepad[] = -{ - // Config number, interface count, string index, total length, attribute, power in mA - TUD_CONFIG_DESCRIPTOR(1, 3, 0, (TUD_CONFIG_DESC_LEN + TUD_CDC_DESC_LEN + TUD_HID_INOUT_DESC_LEN), TUSB_DESC_CONFIG_ATT_REMOTE_WAKEUP, 100), - - // 1st CDC: Interface number, string index, EP notification address and size, EP data address (out, in) and size. - TUD_CDC_DESCRIPTOR(0, 4, 0x82, 8, 0x01, 0x81, 64), - - // HID Descriptor. EP 83 and 2 - TUD_HID_INOUT_DESCRIPTOR(2, 5, HID_ITF_PROTOCOL_NONE, USB_HID_GAMEPAD_REPORT_DESC_SIZE, 0x83, 0x02, 64, HID_BINTERVAL), -}; + const uint8_t usb_cdc_hid_conf_gamepad[] ={USB_CONF_DESC_HID_CDC(USB_HID_GAMEPAD_REPORT_DESC_SIZE,64)}; #endif // Composite CDC and MIDI uint8_t const usb_cdc_midi_conf[] = { // Config number, interface count, string index, total length, attribute, power in mA - TUD_CONFIG_DESCRIPTOR(1, 4, 0, TUD_CONFIG_DESC_LEN + TUD_CDC_DESC_LEN + TUD_MIDI_DESC_LEN, TUSB_DESC_CONFIG_ATT_REMOTE_WAKEUP, 100), + TUD_CONFIG_DESCRIPTOR(1, 4, 0, TUD_CONFIG_DESC_LEN + TUD_CDC_DESC_LEN + TUD_MIDI_DESC_LEN, TUSB_DESC_CONFIG_ATT_REMOTE_WAKEUP | TUSB_DESC_CONFIG_ATT_SELF_POWERED, 100), // 1st CDC: Interface number, string index, EP notification address and size, EP data address (out, in) and size. TUD_CDC_DESCRIPTOR(0, 4, 0x82, 8, 0x01, 0x81, 64), // Interface number, string index, EP Out & EP In address, EP size diff --git a/Firmware/FFBoard/UserExtensions/Src/usb_hid_1ffb_desc.c b/Firmware/FFBoard/UserExtensions/Src/usb_hid_1ffb_desc.c index 3d1e30b26..afbc27caa 100644 --- a/Firmware/FFBoard/UserExtensions/Src/usb_hid_1ffb_desc.c +++ b/Firmware/FFBoard/UserExtensions/Src/usb_hid_1ffb_desc.c @@ -13,231 +13,17 @@ __ALIGN_BEGIN const uint8_t hid_1ffb_desc[USB_HID_1FFB_REPORT_DESC_SIZE] __ALIGN_END = { - 0x05, 0x01, // USAGE_PAGE (Generic Desktop) - 0x09, 0x04, // USAGE (Joystick) - 0xa1, 0x01, // COLLECTION (Application) - 0xa1, 0x00, // COLLECTION (Physical) - 0x85, 0x01, // REPORT_ID (1) - 0x05, 0x09, // USAGE_PAGE (Button) - 0x19, 0x01, // USAGE_MINIMUM (Button 1) - 0x29, 0x40, // USAGE_MAXIMUM (Button 64) - 0x15, 0x00, // LOGICAL_MINIMUM (0) - 0x25, 0x01, // LOGICAL_MAXIMUM (1) - 0x95, 0x40, // REPORT_COUNT (64) - 0x75, 0x01, // REPORT_SIZE (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - 0x05, 0x01, // USAGE_PAGE (Generic Desktop) - 0x09, HID_USAGE_X, // USAGE (X) - 0x09, HID_USAGE_Y, // USAGE (Y) - 0x09, HID_USAGE_Z, // USAGE (Z) - 0x09, HID_USAGE_RX, // USAGE (Rx) - 0x09, HID_USAGE_RY, // USAGE (Ry) - 0x09, HID_USAGE_RZ, // USAGE (Rz) - 0x09, HID_USAGE_SL1, // USAGE (Dial) - 0x09, HID_USAGE_SL0, // USAGE (Slider) - 0x16, 0x01, 0x80, // LOGICAL_MINIMUM (-32767) - 0x26, 0xff, 0x7f, // LOGICAL_MAXIMUM (32767) - 0x75, 0x10, // REPORT_SIZE (16) - 0x95, 0x08, // REPORT_COUNT (8) - 0x81, 0x02, // INPUT (Data,Var,Abs) - 0xc0, // END_COLLECTION - - - // Control reports - 0x06, 0x00, 0xFF, // USAGE_PAGE (Vendor) - 0x09, 0x00, // USAGE (Vendor) - 0xA1, 0x01, // Collection (Application) - - 0x85,HID_ID_HIDCMD, // Report ID - 0x09, 0x01, // USAGE (Vendor) - 0x15, 0x00, // LOGICAL_MINIMUM (0) - 0x26, 0x04, 0x00, // Logical Maximum 4 - 0x75, 0x08, // REPORT_SIZE (8) - 0x95, 0x01, // REPORT_COUNT (1) - 0x91, 0x02, // OUTPUT (Data,Var,Abs) - - 0x09, 0x02, // USAGE (Vendor) class address - 0x75, 0x10, // REPORT_SIZE (16) - 0x95, 0x01, // REPORT_COUNT (1) - 0x91, 0x02, // OUTPUT (Data,Var,Abs) - - 0x09, 0x03, // USAGE (Vendor) class instance - 0x75, 0x08, // REPORT_SIZE (8) - 0x95, 0x01, // REPORT_COUNT (1) - 0x91, 0x02, // OUTPUT (Data,Var,Abs) - - 0x09, 0x04, // USAGE (Vendor) cmd - 0x75, 0x20, // REPORT_SIZE (32) - 0x95, 0x01, // REPORT_COUNT (1) - 0x91, 0x02, // OUTPUT (Data,Var,Abs) - - 0x09, 0x05, // USAGE (Vendor) - 0x75, 0x40, // REPORT_SIZE (64) value - 0x95, 0x01, // REPORT_COUNT (1) - 0x91, 0x02, // OUTPUT (Data,Var,Abs) - - 0x09, 0x06, // USAGE (Vendor) address - 0x75, 0x40, // REPORT_SIZE (64) - 0x95, 0x01, // REPORT_COUNT (1) - 0x91, 0x02, // OUTPUT (Data,Var,Abs) - - 0x85,HID_ID_HIDCMD, // Report ID - 0x09, 0x01, // USAGE (Vendor) - 0x15, 0x00, // LOGICAL_MINIMUM (0) - 0x26, 0x04, 0x00, // Logical Maximum 4 - 0x75, 0x08, // REPORT_SIZE (8) - 0x95, 0x01, // REPORT_COUNT (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - - 0x09, 0x02, // USAGE (Vendor) class address - 0x75, 0x10, // REPORT_SIZE (16) - 0x95, 0x01, // REPORT_COUNT (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - - 0x09, 0x03, // USAGE (Vendor) class instance - 0x75, 0x08, // REPORT_SIZE (8) - 0x95, 0x01, // REPORT_COUNT (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - - 0x09, 0x04, // USAGE (Vendor) cmd - 0x75, 0x20, // REPORT_SIZE (32) - 0x95, 0x01, // REPORT_COUNT (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - - 0x09, 0x05, // USAGE (Vendor) - 0x75, 0x40, // REPORT_SIZE (64) value - 0x95, 0x01, // REPORT_COUNT (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - - 0x09, 0x06, // USAGE (Vendor) address - 0x75, 0x40, // REPORT_SIZE (64) - 0x95, 0x01, // REPORT_COUNT (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - - - - 0xc0, // END_COLLECTION - - - // BEGIN PID effects - 0x05,0x0F, // Usage Page Physical Interface - 0x09,0x92, // Usage PID State report - 0xA1,0x02, // Collection Datalink (logical) - 0x85,HID_ID_STATE+FFB_ID_OFFSET, // Report ID 2 - -// 0x09,0x22, // Usage Effect Block Index -// 0x15,0x01, // Logical Minimum 1 -// 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) -// 0x35,0x01, // Physical Minimum 1 -// 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) -// 0x75,0x08, // Report Size 8 -// 0x95,0x01, // Report Count 1 -// 0x81,0x02, // Input (Variable) - - - - 0x09,0x9F, // Usage Device is Pause - 0x09,0xA0, // Usage Actuators Enabled - 0x09,0xA4, // Usage Safety Switch - 0x09,0xA6, // Usage Actuator Power - - 0x09,0x94, // Usage Effect Playing - /* - 0x15,0x00, // Logical Minimum 0 - 0x25,0x01, // Logical Maximum 1 - 0x35,0x00, // Physical Minimum 0 - 0x45,0x01, // Physical Maximum 1 - 0x75,0x01, // Report Size 1 - 0x95,0x01, // Report Count 1 - 0x81,0x02, // Input (Variable)*/ //14 + 0x05, 0x01, /* USAGE_PAGE (Generic Desktop)*/ + 0x09, 0x04, /* USAGE (Joystick)*/ + 0xa1, 0x01, /* COLLECTION (Application)*/ + HIDDESC_GAMEPAD_16B, - 0x15,0x00, // Logical Minimum 0 - 0x25,0x01, // Logical Maximum 1 - 0x35,0x00, // Physical Minimum 0 - 0x45,0x01, // Physical Maximum 1 - 0x75,0x01, // Report Size 1 - 0x95,0x05, // Report Count 4 - 0x81,0x02, // Input (Variable) - 0x95,0x03, // Report Count 3 - 0x81,0x03, // Input (Constant, Variable) - 0xC0 , // End Collection + HIDDESC_CTRL_REPORTS, // HID command report support - /* - Output - Collection Datalink: - Usage Set Effect Report - ID:1 - Effect Block Index: 8bit + HIDDESC_FFB_STATEREP, - subcollection Effect Type - 12 effect types, 8bit each - - */ - 0x09,0x21, // Usage Set Effect Report - 0xA1,0x02, // Collection Datalink (Logical) - 0x85,HID_ID_EFFREP+FFB_ID_OFFSET, // Report ID 1 - 0x09,0x22, // Usage Effect Block Index - 0x15,0x01, // Logical Minimum 1 - 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) - 0x35,0x01, // Physical Minimum 1 - 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0x09,0x25, // Usage Effect Type - 0xA1,0x02, // Collection Datalink - 0x09, HID_USAGE_CONST, // Usage ET Constant Force - 0x09, HID_USAGE_RAMP, // Usage ET Ramp - 0x09, HID_USAGE_SQUR, // Usage ET Square - 0x09, HID_USAGE_SINE, // Usage ET Sine - 0x09, HID_USAGE_TRNG, // Usage ET Triangle - 0x09, HID_USAGE_STUP, // Usage ET Sawtooth Up - 0x09, HID_USAGE_STDN, // Usage ET Sawtooth Down - 0x09, HID_USAGE_SPRNG, // Usage ET Spring - 0x09, HID_USAGE_DMPR, // Usage ET Damper - 0x09, HID_USAGE_INRT, // Usage ET Inertia - 0x09, HID_USAGE_FRIC, // Usage ET Friction - // 0x09, 0x28, // Usage ET Custom Force Data - 0x25,0x0B, // Logical Maximum Bh (11d) - 0x15,0x01, // Logical Minimum 1 - 0x35,0x01, // Physical Minimum 1 - 0x45,0x0B, // Physical Maximum Bh (11d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x00, // Output - 0xC0 , // End Collection - 0x09,0x50, // Usage Duration - 0x09,0x54, // Usage Trigger Repeat Interval - 0x09,0x51, // Usage Sample Period - 0x09,0xA7, // Usage Start Delay - 0x15,0x00, // Logical Minimum 0 - 0x26,0xFF,0x7F, // Logical Maximum 7FFFh (32767d) - 0x35,0x00, // Physical Minimum 0 - 0x46,0xFF,0x7F, // Physical Maximum 7FFFh (32767d) - 0x66,0x03,0x10, // Unit 1003h (4099d) - 0x55,0xFD, // Unit Exponent FDh (253d) - 0x75,0x10, // Report Size 10h (16d) - 0x95,0x04, // Report Count 4 - 0x91,0x02, // Output (Variable) - 0x55,0x00, // Unit Exponent 0 - 0x66,0x00,0x00, // Unit 0 - 0x09,0x52, // Usage Gain - 0x15,0x00, // Logical Minimum 0 - 0x26,0xFF,0x00, // Logical Maximum FFh (255d) // TODO scaling? - 0x35,0x00, // Physical Minimum 0 - 0x46,0x10,0x27, // Physical Maximum 2710h (10000d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0x09,0x53, // Usage Trigger Button - 0x15,0x01, // Logical Minimum 1 - 0x25,0x08, // Logical Maximum 8 - 0x35,0x01, // Physical Minimum 1 - 0x45,0x08, // Physical Maximum 8 - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) + HIDDESC_FFB_SETEFREP, 0x09,0x55, // Usage Axes Enable TODO multi axis 0xA1,0x02, // Collection Datalink @@ -289,39 +75,8 @@ __ALIGN_BEGIN const uint8_t hid_1ffb_desc[USB_HID_1FFB_REPORT_DESC_SIZE] __ALIGN 0xC0, // END_COLLECTION 0xC0, // END_COLLECTION - // Envelope Report Definition - 0x09,0x5A, // Usage Set Envelope Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_ENVREP+FFB_ID_OFFSET, // Report ID 2 - 0x09,0x22, // Usage Effect Block Index - 0x15,0x01, // Logical Minimum 1 - 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) - 0x35,0x01, // Physical Minimum 1 - 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0x09,0x5B, // Usage Attack Level - 0x09,0x5D, // Usage Fade Level - 0x16,0x00,0x00, // Logical Minimum 0 - 0x26,0xFF,0x7F, // Logical Maximum 7FFFh (32767d) - 0x36,0x00,0x00, // Physical Minimum 0 - 0x46,0xFF,0x7F, // Physical Maximum 7FFFh (32767d) - 0x75,0x10, // Report Size 16 - 0x95,0x02, // Report Count 2 - 0x91,0x02, // Output (Variable) - 0x09, 0x5C, // Usage Attack Time - 0x09, 0x5E, // Usage Fade Time - 0x66, 0x03, 0x10, // Unit 1003h (English Linear, Seconds) - 0x55, 0xFD, // Unit Exponent FDh (X10^-3 ==> Milisecond) - 0x27, 0xFF, 0x7F, 0x00, 0x00, // Logical Maximum FFFFFFFFh (4294967295) - 0x47, 0xFF, 0x7F, 0x00, 0x00, // Physical Maximum FFFFFFFFh (4294967295) - 0x75, 0x20, // Report Size 20h (32d) - 0x91, 0x02, // Output (Variable) - 0x45, 0x00, // Physical Maximum 0 - 0x66,0x00,0x00, // Unit 0 - 0x55,0x00, // Unit Exponent 0 - 0xC0 , // End Collection + HIDDESC_FFB_SETENVREP, + 0x09,0x5F, // Usage Set Condition Report 0xA1,0x02, // Collection Datalink 0x85,HID_ID_CONDREP+FFB_ID_OFFSET, // Report ID 3 @@ -378,97 +133,12 @@ __ALIGN_BEGIN const uint8_t hid_1ffb_desc[USB_HID_1FFB_REPORT_DESC_SIZE] __ALIGN 0x95,0x01, // Report Count 1 0x91,0x02, // Output (Variable) 0xC0 , // End Collection - 0x09,0x6E, // Usage Set Periodic Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_PRIDREP+FFB_ID_OFFSET, // Report ID 4 - 0x09,0x22, // Usage Effect Block Index - 0x15,0x01, // Logical Minimum 1 - 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) - 0x35,0x01, // Physical Minimum 1 - 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0x09,0x70, // Usage Magnitude - 0x16,0x00,0x00, // Logical Minimum 0 - 0x26,0xff, 0x7f, // Logical Maximum 7FFFh (32767d) - 0x36,0x00,0x00, // Physical Minimum 0 - 0x26,0xff, 0x7f, // Logical Maximum 7FFFh (32767d) - 0x75,0x10, // Report Size 16 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0x09, 0x6F, // Usage Offset - 0x16,0x00, 0x80, // Logical Minimum 7FFFh (-32767d) - 0x26,0xff, 0x7f, // Logical Maximum 7FFFh (32767d) - 0x36,0x00, 0x80, // Physical Minimum 7FFFh (-32767d) - 0x46,0xff, 0x7f, // Physical Maximum 7FFFh (32767d) - 0x95, 0x01, // Report Count 1 - 0x75, 0x10, // Report Size 16 - 0x91, 0x02, // Output (Variable) - 0x09, 0x71, // Usage Phase - 0x66, 0x14, 0x00, // Unit 14h (Eng Rotation, Degrees) - 0x55, 0xFE, // Unit Exponent FEh (X10^-2) - 0x15, 0x00, // Logical Minimum 0 - 0x27, 0x9F, 0x8C, 0x00, 0x00, // Logical Maximum 8C9Fh (35999d) - 0x35, 0x00, // Physical Minimum 0 - 0x47, 0x9F, 0x8C, 0x00, 0x00, // Physical Maximum 8C9Fh (35999d) - 0x75, 0x10, // Report Size 16 - 0x95, 0x01, // Report Count 1 - 0x91, 0x02, // Output (Variable) - 0x09, 0x72, // Usage Period - 0x15, 0x01, // Logical Minimum 1 - 0x27, 0xFF, 0x7F, 0x00, 0x00, // Logical Maximum 7FFFh (32K) - 0x35, 0x01, // Physical Minimum 1 - 0x47, 0xFF, 0x7F, 0x00, 0x00, // Physical Maximum 7FFFh (32K) - 0x66, 0x03, 0x10, // Unit 1003h (English Linear, Seconds) - 0x55, 0xFD, // Unit Exponent FDh (X10^-3 ==> Milisecond) - 0x75, 0x20, // Report Size 20h (32) - 0x95, 0x01, // Report Count 1 - 0x91, 0x02, // Output (Variable) - 0x66, 0x00, 0x00, // Unit 0 - 0x55,0x00, // Unit Exponent 0 - 0xC0 , // End Collection - 0x09,0x73, // Usage Set Constant Force Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_CONSTREP+FFB_ID_OFFSET, // Report ID 5 - 0x09,0x22, // Usage Effect Block Index - 0x15,0x01, // Logical Minimum 1 - 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) - 0x35,0x01, // Physical Minimum 1 - 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0x09,0x70, // Usage Magnitude - 0x16,0x00, 0x80, // Logical Minimum 7FFFh (-32767d) - 0x26,0xff, 0x7f, // Logical Maximum 7FFFh (32767d) - 0x36,0x00, 0x80, // Physical Minimum 7FFFh (-32767d) - 0x46,0xff, 0x7f, // Physical Maximum 7FFFh (32767d) - 0x75, 0x10, // Report Size 10h (16d) - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0xC0 , // End Collection - 0x09,0x74, // Usage Set Ramp Force Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_RAMPREP+FFB_ID_OFFSET, // Report ID 6 - 0x09,0x22, // Usage Effect Block Index - 0x15,0x01, // Logical Minimum 1 - 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) - 0x35,0x01, // Physical Minimum 1 - 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0x09,0x75, // Usage Ramp Start - 0x09,0x76, // Usage Ramp End - 0x16,0x00, 0x80, // Logical Minimum 7FFFh (-32767d) - 0x26,0xff, 0x7f, // Logical Maximum 7FFFh (32767d) - 0x36,0x00, 0x80, // Physical Minimum 7FFFh (-32767d) - 0x46,0xff, 0x7f, // Physical Maximum 7FFFh (32767d) - 0x75,0x10, // Report Size 16 - 0x95,0x02, // Report Count 2 - 0x91,0x02, // Output (Variable) - 0xC0 , // End Collection + + HIDDESC_FFB_SETPERIODICREP, + + HIDDESC_FFB_SETCFREP, + + HIDDESC_FFB_SETRAMPREP, // 0x09,0x68, // Usage Custom Force Data Report @@ -514,84 +184,10 @@ __ALIGN_BEGIN const uint8_t hid_1ffb_desc[USB_HID_1FFB_REPORT_DESC_SIZE] __ALIGN // 0x91,0x02, // Output (Variable) // 0xC0 , // End Collection - 0x05,0x0F, // Usage Page Physical Interface - 0x09,0x77, // Usage Effect Operation Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_EFOPREP+FFB_ID_OFFSET, // Report ID Ah (10d) - 0x09,0x22, // Usage Effect Block Index - 0x15,0x01, // Logical Minimum 1 - 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) - 0x35,0x01, // Physical Minimum 1 - 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0x09,0x78, // Usage Effect Operation - 0xA1,0x02, // Collection Datalink - 0x09,0x79, // Usage Op Effect Start - 0x09,0x7A, // Usage Op Effect Start Solo - 0x09,0x7B, // Usage Op Effect Stop - 0x15,0x01, // Logical Minimum 1 - 0x25,0x03, // Logical Maximum 3 - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x00, // Output - 0xC0 , // End Collection - 0x09,0x7C, // Usage Loop Count - 0x15,0x00, // Logical Minimum 0 - 0x26,0xFF,0x00, // Logical Maximum FFh (255d) - 0x35,0x00, // Physical Minimum 0 - 0x46,0xFF,0x00, // Physical Maximum FFh (255d) - 0x91,0x02, // Output (Variable) - 0xC0 , // End Collection - 0x09,0x90, // Usage PID Block Free Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_BLKFRREP+FFB_ID_OFFSET, // Report ID Bh (11d) - 0x09,0x22, // Usage Effect Block Index - 0x15,0x01, // Logical Minimum 1 - 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) - 0x35,0x01, // Physical Minimum 1 - 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0xC0 , // End Collection - - 0x09,0x95, // Usage PID Device Control (0x96?) - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_CTRLREP+FFB_ID_OFFSET, // Report ID Ch (12d) - 0x09,0x96, // Usage PID Device Control (0x96?) - 0xA1,0x02, // Collection Datalink - - 0x09,0x97, // Usage DC Enable Actuators - 0x09,0x98, // Usage DC Disable Actuators - 0x09,0x99, // Usage DC Stop All Effects - 0x09,0x9A, // Usage DC Device Reset - 0x09,0x9B, // Usage DC Device Pause - 0x09,0x9C, // Usage DC Device Continue - - + HIDDESC_FFB_EFOPREP, + HIDDESC_FFB_BLOCKFREEREP, - 0x15,0x01, // Logical Minimum 1 - 0x25,0x06, // Logical Maximum 6 - 0x75,0x01, // Report Size 1 - 0x95,0x08, // Report Count 8 - 0x91,0x02, // Output - - 0xC0 , // End Collection - 0xC0 , // End Collection - 0x09,0x7D, // Usage Device Gain Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_GAINREP+FFB_ID_OFFSET, // Report ID Dh (13d) - 0x09,0x7E, // Usage Device Gain - 0x15,0x00, // Logical Minimum 0 - 0x26,0xFF,0x00, // Logical Maximum FFh (255d) - 0x35,0x00, // Physical Minimum 0 - 0x46,0x10,0x27, // Physical Maximum 2710h (10000d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0xC0 , // End Collection + HIDDESC_FFB_DEVCTRLREP, // 0x09,0x6B, // Usage Set Custom Force Report // 0xA1,0x02, // Collection Datalink // 0x85,HID_ID_SETCREP+FFB_ID_OFFSET, // Report ID Eh (14d) @@ -624,110 +220,168 @@ __ALIGN_BEGIN const uint8_t hid_1ffb_desc[USB_HID_1FFB_REPORT_DESC_SIZE] __ALIGN // 0x55,0x00, // Unit Exponent 0 // 0x66,0x00,0x00, // Unit 0 // 0xC0 , // End Collection - 0x09,0xAB, // Usage Create New Effect Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_NEWEFREP+FFB_ID_OFFSET, // Report ID 1 - 0x09,0x25, // Usage Effect Type + HIDDESC_FFB_NEWEFREP, + HIDDESC_FFB_BLOCKLOADREP, + + HIDDESC_FFB_POOLREP, + + 0xC0 /* END_COLLECTION */ +}; +#endif + +#ifdef AXIS1_FFB_HID_DESC_32B +__ALIGN_BEGIN const uint8_t hid_1ffb_desc_32b[USB_HID_1FFB_REPORT_DESC_32B_SIZE] __ALIGN_END = +{ + 0x05, 0x01, /* USAGE_PAGE (Generic Desktop)*/ + 0x09, 0x04, /* USAGE (Joystick)*/ + 0xa1, 0x01, /* COLLECTION (Application)*/ + HIDDESC_GAMEPAD_32B, + + HIDDESC_CTRL_REPORTS, // HID command report support + + HIDDESC_FFB_STATEREP, + /* + Output + Collection Datalink: + Usage Set Effect Report + + ID:1 + Effect Block Index: 8bit + + subcollection Effect Type + 12 effect types, 8bit each + + */ + HIDDESC_FFB_SETEFREP, + + 0x09,0x55, // Usage Axes Enable TODO multi axis + 0xA1,0x02, // Collection Datalink + 0x05,0x01, // Usage Page Generic Desktop + 0x09,0x30, // Usage X + //0x09,0x31, // Usage Y + 0x15,0x00, // Logical Minimum 0 + 0x25,0x00, // Logical Maximum 0 + 0x75,0x01, // Report Size 1 + 0x95,0x01, // Report Count 1 + 0x91,0x02, // Output (Variable) + 0xC0 , // End Collection + 0x05,0x0F, // Usage Page Physical Interface + 0x09,0x56, // Usage Direction Enable + 0x95,0x01, // Report Count 1 + 0x91,0x02, // Output (Variable) + 0x95,0x06, // Report Count 6 + 0x91,0x03, // Output (Constant, Variable) + + 0x09,0x57, // Usage Direction 0xA1,0x02, // Collection Datalink - 0x09, HID_USAGE_CONST, // Usage ET Constant Force - 0x09, HID_USAGE_RAMP, // Usage ET Ramp - 0x09, HID_USAGE_SQUR, // Usage ET Square - 0x09, HID_USAGE_SINE, // Usage ET Sine - 0x09, HID_USAGE_TRNG, // Usage ET Triangle - 0x09, HID_USAGE_STUP, // Usage ET Sawtooth Up - 0x09, HID_USAGE_STDN, // Usage ET Sawtooth Down - 0x09, HID_USAGE_SPRNG, // Usage ET Spring - 0x09, HID_USAGE_DMPR, // Usage ET Damper - 0x09, HID_USAGE_INRT, // Usage ET Inertia - 0x09, HID_USAGE_FRIC, // Usage ET Friction -// 0x09, 0x28, // Usage ET Custom Force Data - 0x25,0x0B, // Logical Maximum Ch (11d) + 0x0B,0x01,0x00,0x0A,0x00, // Usage Ordinals: Instance 1 +// 0x0B,0x02,0x00,0x0A,0x00, // Usage Ordinals: Instance 2 + 0x66,0x14,0x00, // Unit 14h (20d) +// 0x55,0xFE, // Unit Exponent FEh (254d) +// 0x15,0x00, // Logical Minimum 0 +// 0x26,0xFF,0x00, // Logical Maximum FFh (255d) + 0x15,0x00, // Logical Minimum 0 + 0x27,0xA0,0x8C,0x00,0x00, // Logical Maximum 8CA0h (36000d) + 0x35,0x00, // Physical Minimum 0 + 0x47,0xA0,0x8C,0x00,0x00, // Physical Maximum 8CA0h (36000d) + 0x66,0x00,0x00, // Unit 0 + 0x75,0x10, // Report Size 16 + 0x95,0x01, // Report Count 1 + 0x91,0x02, // Output (Variable) + 0x55,0x00, // Unit Exponent 0 + 0x66,0x00,0x00, // Unit 0 + 0xC0, // End Collection + + 0x05, 0x0F, // USAGE_PAGE (Physical Interface) + 0x09, 0x58, // USAGE (Type Specific Block Offset) + 0xA1, 0x02, // COLLECTION (Logical) + 0x0B, 0x01, 0x00, 0x0A, 0x00, //USAGE (Ordinals:Instance 1 + //0x0B, 0x02, 0x00, 0x0A, 0x00, //USAGE (Ordinals:Instance 2) + 0x26, 0xFD, 0x7F, // LOGICAL_MAXIMUM (32765) ; 32K RAM or ROM max. + 0x75, 0x10, // REPORT_SIZE (16) + 0x95, 0x01, // REPORT_COUNT (1) + 0x91, 0x02, // OUTPUT (Data,Var,Abs) + 0xC0, // END_COLLECTION + 0xC0, // END_COLLECTION + + HIDDESC_FFB_SETENVREP, + + 0x09,0x5F, // Usage Set Condition Report + 0xA1,0x02, // Collection Datalink + 0x85,HID_ID_CONDREP+FFB_ID_OFFSET, // Report ID 3 + 0x09,0x22, // Usage Effect Block Index 0x15,0x01, // Logical Minimum 1 + 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) 0x35,0x01, // Physical Minimum 1 - 0x45,0x0B, // Physical Maximum Ch (11d) + 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) 0x75,0x08, // Report Size 8 0x95,0x01, // Report Count 1 - 0xB1,0x00, // Feature - 0xC0 , // End Collection - 0x05,0x01, // Usage Page Generic Desktop - 0x09,0x3B, // Usage Reserved (Byte count) - 0x15,0x00, // Logical Minimum 0 - 0x26,0xFF,0x01, // Logical Maximum 1FFh (511d) - 0x35,0x00, // Physical Minimum 0 - 0x46,0xFF,0x01, // Physical Maximum 1FFh (511d) - 0x75,0x0A, // Report Size Ah (10d) - 0x95,0x01, // Report Count 1 - 0xB1,0x02, // Feature (Variable) - 0x75,0x06, // Report Size 6 - 0xB1,0x01, // Feature (Constant) - 0xC0 , // End Collection - 0x05,0x0F, // Usage Page Physical Interface - 0x09,0x89, // Usage Block Load Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_BLKLDREP+FFB_ID_OFFSET, // Report ID 0x12 - 0x09,0x22, // Usage Effect Block Index - 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) - 0x15,0x01, // Logical Minimum 1 - 0x35,0x01, // Physical Minimum 1 - 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0xB1,0x02, // Feature (Variable) - 0x09,0x8B, // Usage Block Load Status - 0xA1,0x02, // Collection Datalink - 0x09,0x8C, // Usage Block Load Success - 0x09,0x8D, // Usage Block Load Full - 0x09,0x8E, // Usage Block Load Error - 0x15,0x01, // Logical Minimum 1 + 0x91,0x02, // Output (Variable) + 0x09,0x23, // Usage Parameter Block Offset + 0x15,0x00, // Logical Minimum 0 0x25,0x03, // Logical Maximum 3 - 0x35,0x01, // Physical Minimum 1 + 0x35,0x00, // Physical Minimum 0 0x45,0x03, // Physical Maximum 3 - 0x75,0x08, // Report Size 8 + 0x75,0x06, // Report Size 6 0x95,0x01, // Report Count 1 - 0xB1,0x00, // Feature - 0xC0 , // End Collection - 0x09,0xAC, // Usage Pool available - 0x15,0x00, // Logical Minimum 0 - 0x27,0xFF,0xFF,0x00,0x00, // Logical Maximum FFFFh (65535d) - 0x35,0x00, // Physical Minimum 0 - 0x47,0xFF,0xFF,0x00,0x00, // Physical Maximum FFFFh (65535d) - 0x75,0x10, // Report Size 10h (16d) - 0x95,0x01, // Report Count 1 - 0xB1,0x00, // Feature + 0x91,0x02, // Output (Variable) + 0x09,0x58, // Usage Type Specific Block Off... + 0xA1,0x02, // Collection Datalink + 0x0B,0x01,0x00,0x0A,0x00, // Usage Ordinals: Instance 1 +// 0x0B,0x02,0x00,0x0A,0x00, // Usage Ordinals: Instance 2 + 0x75,0x02, // Report Size 2 + 0x95,0x01, // Report Count 1 + 0x91,0x02, // Output (Variable) + 0xC0 , // End Collection + 0x16,0x00, 0x80, // Logical Minimum 7FFFh (-32767d) + 0x26,0xff, 0x7f, // Logical Maximum 7FFFh (32767d) + 0x36,0x00, 0x80, // Physical Minimum 7FFFh (-32767d) + 0x46,0xff, 0x7f, // Physical Maximum 7FFFh (32767d) + + 0x09,0x60, // Usage CP Offset + 0x75,0x10, // Report Size 16 + 0x95,0x01, // Report Count 1 + 0x91,0x02, // Output (Variable) + 0x36,0x00, 0x80, // Physical Minimum (-32768) + 0x46,0xff, 0x7f, // Physical Maximum (32767) + 0x09,0x61, // Usage Positive Coefficient + 0x09,0x62, // Usage Negative Coefficient + 0x95,0x02, // Report Count 2 + 0x91,0x02, // Output (Variable) + 0x16,0x00,0x00, // Logical Minimum 0 + 0x26,0xff, 0x7f, // Logical Maximum (32767) + 0x36,0x00,0x00, // Physical Minimum 0 + 0x46,0xff, 0x7f, // Physical Maximum (32767) + 0x09,0x63, // Usage Positive Saturation + 0x09,0x64, // Usage Negative Saturation + 0x75,0x10, // Report Size 16 + 0x95,0x02, // Report Count 2 + 0x91,0x02, // Output (Variable) + 0x09,0x65, // Usage Dead Band + 0x46,0xff, 0x7f, // Physical Maximum (32767) + 0x95,0x01, // Report Count 1 + 0x91,0x02, // Output (Variable) 0xC0 , // End Collection - 0x09,0x7F, // Usage PID Pool Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_POOLREP+FFB_ID_OFFSET, // Report ID 0x13 - 0x09,0x80, // Usage RAM Pool size - 0x75,0x10, // Report Size 10h (16d) - 0x95,0x01, // Report Count 1 - 0x15,0x00, // Logical Minimum 0 - 0x35,0x00, // Physical Minimum 0 - 0x27,0xFF,0xFF,0x00,0x00, // Logical Maximum FFFFh (65535d) - 0x47,0xFF,0xFF,0x00,0x00, // Physical Maximum FFFFh (65535d) - 0xB1,0x02, // Feature (Variable) - 0x09,0x83, // Usage Simultaneous Effects Max - 0x26,0xFF,0x00, // Logical Maximum FFh (255d) - 0x46,0xFF,0x00, // Physical Maximum FFh (255d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0xB1,0x02, // Feature (Variable) - 0x09,0xA9, // Usage Device Managed Pool - 0x09,0xAA, // Usage Shared Parameter Blocks - 0x75,0x01, // Report Size 1 - 0x95,0x02, // Report Count 2 - 0x15,0x00, // Logical Minimum 0 - 0x25,0x01, // Logical Maximum 1 - 0x35,0x00, // Physical Minimum 0 - 0x45,0x01, // Physical Maximum 1 - 0xB1,0x02, // Feature (Variable) - 0x75,0x06, // Report Size 6 - 0x95,0x01, // Report Count 1 - 0xB1,0x03, // Feature (Constant, Variable) - 0xC0, // End Collection + HIDDESC_FFB_SETPERIODICREP, + + HIDDESC_FFB_SETCFREP, + + HIDDESC_FFB_SETRAMPREP, + + HIDDESC_FFB_EFOPREP, + + HIDDESC_FFB_BLOCKFREEREP, + + HIDDESC_FFB_DEVCTRLREP, + + HIDDESC_FFB_NEWEFREP, + + HIDDESC_FFB_BLOCKLOADREP, + + HIDDESC_FFB_POOLREP, 0xC0 /* END_COLLECTION */ }; - #endif + diff --git a/Firmware/FFBoard/UserExtensions/Src/usb_hid_2ffb_desc.c b/Firmware/FFBoard/UserExtensions/Src/usb_hid_2ffb_desc.c index 79e98bcb0..6083e7e52 100644 --- a/Firmware/FFBoard/UserExtensions/Src/usb_hid_2ffb_desc.c +++ b/Firmware/FFBoard/UserExtensions/Src/usb_hid_2ffb_desc.c @@ -12,210 +12,95 @@ #ifdef AXIS2_FFB_HID_DESC __ALIGN_BEGIN const uint8_t hid_2ffb_desc[USB_HID_2FFB_REPORT_DESC_SIZE] __ALIGN_END = { - 0x05, 0x01, // USAGE_PAGE (Generic Desktop) - 0x09, 0x04, // USAGE (Joystick) - 0xa1, 0x01, // COLLECTION (Application) - 0xa1, 0x00, // COLLECTION (Physical) - 0x85, 0x01, // REPORT_ID (1) - 0x05, 0x09, // USAGE_PAGE (Button) - 0x19, 0x01, // USAGE_MINIMUM (Button 1) - 0x29, 0x40, // USAGE_MAXIMUM (Button 64) - 0x15, 0x00, // LOGICAL_MINIMUM (0) - 0x25, 0x01, // LOGICAL_MAXIMUM (1) - 0x95, 0x40, // REPORT_COUNT (64) - 0x75, 0x01, // REPORT_SIZE (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - 0x05, 0x01, // USAGE_PAGE (Generic Desktop) - 0x09, HID_USAGE_X, // USAGE (X) - 0x09, HID_USAGE_Y, // USAGE (Y) - 0x09, HID_USAGE_Z, // USAGE (Z) - 0x09, HID_USAGE_RX, // USAGE (Rx) - 0x09, HID_USAGE_RY, // USAGE (Ry) - 0x09, HID_USAGE_RZ, // USAGE (Rz) - 0x09, HID_USAGE_SL1, // USAGE (Dial) - 0x09, HID_USAGE_SL0, // USAGE (Slider) - 0x16, 0x01, 0x80, // LOGICAL_MINIMUM (-32767) - 0x26, 0xff, 0x7f, // LOGICAL_MAXIMUM (32767) - 0x75, 0x10, // REPORT_SIZE (16) - 0x95, 0x08, // REPORT_COUNT (8) - 0x81, 0x02, // INPUT (Data,Var,Abs) - 0xc0, // END_COLLECTION - - - // Control reports - 0x06, 0x00, 0xFF, // USAGE_PAGE (Vendor) - 0x09, 0x00, // USAGE (Vendor) - 0xA1, 0x01, // Collection (Application) -// 0x85,HID_ID_CUSTOMCMD, // Report ID -// 0x09, 0x01, // USAGE (Vendor) type -// 0x15, 0x00, // LOGICAL_MINIMUM (0) -// 0x26, 0x04, 0x00, // Logical Maximum 4 -// 0x75, 0x08, // REPORT_SIZE (8) -// 0x95, 0x01, // REPORT_COUNT (1) -// 0xb1, 0x02, // FEATURE (Data,Var,Abs) -// -// 0x09, 0x02, // USAGE (Vendor) cmd -// 0x09, 0x03, // USAGE (Vendor) addr -// 0x75, 0x20, // REPORT_SIZE (32) -// 0x95, 0x02, // REPORT_COUNT (2) -// 0xb1, 0x02, // FEATURE (Data,Var,Abs) -// -// 0x09, 0x04, // USAGE (Vendor) data -// 0x75, 0x40, // REPORT_SIZE (64) -// 0x95, 0x01, // REPORT_COUNT (1) -// 0xb1, 0x02, // FEATURE (Data,Var,Abs) -// -// 0x85,HID_ID_CUSTOMCMD, // Report ID -// 0x09, 0x01, // USAGE (Vendor) -// 0x15, 0x00, // LOGICAL_MINIMUM (0) -// 0x26, 0x04, 0x00, // Logical Maximum 4 -// 0x75, 0x08, // REPORT_SIZE (8) -// 0x95, 0x01, // REPORT_COUNT (1) -// 0x91, 0x02, // OUTPUT (Data,Var,Abs) -// -// 0x09, 0x02, // USAGE (Vendor) -// 0x09, 0x03, // USAGE (Vendor) -// 0x75, 0x20, // REPORT_SIZE (32) -// 0x95, 0x02, // REPORT_COUNT (2) -// 0x91, 0x02, // OUTPUT (Data,Var,Abs) + 0x05, 0x01, /* USAGE_PAGE (Generic Desktop)*/ + 0x09, 0x04, /* USAGE (Joystick)*/ + 0xa1, 0x01, /* COLLECTION (Application)*/ + HIDDESC_GAMEPAD_16B, +// 0x05, 0x01, // USAGE_PAGE (Generic Desktop) +// 0x09, 0x04, // USAGE (Joystick) +// 0xa1, 0x01, // COLLECTION (Application) +// 0xa1, 0x00, // COLLECTION (Physical) +// 0x85, 0x01, // REPORT_ID (1) +// 0x05, 0x09, // USAGE_PAGE (Button) +// 0x19, 0x01, // USAGE_MINIMUM (Button 1) +// 0x29, 0x40, // USAGE_MAXIMUM (Button 64) +// 0x15, 0x00, // LOGICAL_MINIMUM (0) +// 0x25, 0x01, // LOGICAL_MAXIMUM (1) +// 0x95, 0x40, // REPORT_COUNT (64) +// 0x75, 0x01, // REPORT_SIZE (1) +// 0x81, 0x02, // INPUT (Data,Var,Abs) +// 0x05, 0x01, // USAGE_PAGE (Generic Desktop) +// 0x09, HID_USAGE_DESKTOP_X, // USAGE (X) +//#if defined(HIDAXISRES_32B) && MAX_AXIS == 1 +// HIDDESC_32B_ENTRY(0x01) +//#endif +// 0x09, HID_USAGE_DESKTOP_Y, // USAGE (Y) +//#if defined(HIDAXISRES_32B) && MAX_AXIS == 2 +// HIDDESC_32B_ENTRY(0x02) +//#endif +// 0x09, HID_USAGE_DESKTOP_Z, // USAGE (Z) +//#if defined(HIDAXISRES_32B) && MAX_AXIS == 3 +// HIDDESC_32B_ENTRY(0x03) +//#endif +// 0x09, HID_USAGE_DESKTOP_RX, // USAGE (Rx) +// 0x09, HID_USAGE_DESKTOP_RY, // USAGE (Ry) +// 0x09, HID_USAGE_DESKTOP_RZ, // USAGE (Rz) +// 0x09, HID_USAGE_DESKTOP_DIAL, // USAGE (Dial) +// 0x09, HID_USAGE_DESKTOP_SLIDER, // USAGE (Slider) +// 0x16, 0x01, 0x80, // LOGICAL_MINIMUM (-32767) +// 0x26, 0xff, 0x7f, // LOGICAL_MAXIMUM (32767) +// 0x75, 0x10, // REPORT_SIZE (16) +//#if defined(HIDAXISRES_32B) +// 0x95, 0x08-MAX_AXIS, // REPORT_COUNT (8- amount of 32b axes) +//#else +// 0x95, 0x08, // REPORT_COUNT (8) +//#endif +// 0x81, 0x02, // INPUT (Data,Var,Abs) +// 0xc0, // END_COLLECTION + + HIDDESC_CTRL_REPORTS, // HID command report support + + // BEGIN PID effects +// 0x05,0x0F, // Usage Page Physical Interface +// 0x09,0x92, // Usage PID State report +// 0xA1,0x02, // Collection Datalink (logical) +// 0x85,HID_ID_STATE+FFB_ID_OFFSET, // Report ID 2 // -// 0x09, 0x04, // USAGE (Vendor) -// 0x75, 0x40, // REPORT_SIZE (64) -// 0x95, 0x01, // REPORT_COUNT (1) -// 0x91, 0x02, // OUTPUT (Data,Var,Abs) +//// 0x09,0x22, // Usage Effect Block Index +//// 0x15,0x01, // Logical Minimum 1 +//// 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) +//// 0x35,0x01, // Physical Minimum 1 +//// 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) +//// 0x75,0x08, // Report Size 8 +//// 0x95,0x01, // Report Count 1 +//// 0x81,0x02, // Input (Variable) // -// 0x85,HID_ID_CUSTOMCMD, // Report ID -// 0x09, 0x01, // USAGE (Vendor) -// 0x15, 0x00, // LOGICAL_MINIMUM (0) -// 0x26, 0x04, 0x00, // Logical Maximum 4 -// 0x75, 0x08, // REPORT_SIZE (8) -// 0x95, 0x01, // REPORT_COUNT (1) -// 0x81, 0x02, // INPUT (Data,Var,Abs) +// 0x09,0x9F, // Usage Device is Pause +// 0x09,0xA0, // Usage Actuators Enabled +// 0x09,0xA4, // Usage Safety Switch +// 0x09,0xA6, // Usage Actuator Power // -// 0x09, 0x02, // USAGE (Vendor) -// 0x09, 0x03, // USAGE (Vendor) -// 0x75, 0x20, // REPORT_SIZE (32) -// 0x95, 0x02, // REPORT_COUNT (2) -// 0x81, 0x02, // INPUT (Data,Var,Abs) +// 0x09,0x94, // Usage Effect Playing +// /* +// 0x15,0x00, // Logical Minimum 0 +// 0x25,0x01, // Logical Maximum 1 +// 0x35,0x00, // Physical Minimum 0 +// 0x45,0x01, // Physical Maximum 1 +// 0x75,0x01, // Report Size 1 +// 0x95,0x01, // Report Count 1 +// 0x81,0x02, // Input (Variable)*/ //14 // -// 0x09, 0x04, // USAGE (Vendor) -// 0x75, 0x40, // REPORT_SIZE (64) -// 0x95, 0x01, // REPORT_COUNT (1) -// 0x81, 0x02, // INPUT (Data,Var,Abs) - 0x85,HID_ID_HIDCMD, // Report ID - 0x09, 0x01, // USAGE (Vendor) - 0x15, 0x00, // LOGICAL_MINIMUM (0) - 0x26, 0x04, 0x00, // Logical Maximum 4 - 0x75, 0x08, // REPORT_SIZE (8) - 0x95, 0x01, // REPORT_COUNT (1) - 0x91, 0x02, // OUTPUT (Data,Var,Abs) - - 0x09, 0x02, // USAGE (Vendor) class address - 0x75, 0x10, // REPORT_SIZE (16) - 0x95, 0x01, // REPORT_COUNT (1) - 0x91, 0x02, // OUTPUT (Data,Var,Abs) - - 0x09, 0x03, // USAGE (Vendor) class instance - 0x75, 0x08, // REPORT_SIZE (8) - 0x95, 0x01, // REPORT_COUNT (1) - 0x91, 0x02, // OUTPUT (Data,Var,Abs) - - 0x09, 0x04, // USAGE (Vendor) cmd - 0x75, 0x20, // REPORT_SIZE (32) - 0x95, 0x01, // REPORT_COUNT (1) - 0x91, 0x02, // OUTPUT (Data,Var,Abs) - - 0x09, 0x05, // USAGE (Vendor) - 0x75, 0x40, // REPORT_SIZE (64) value - 0x95, 0x01, // REPORT_COUNT (1) - 0x91, 0x02, // OUTPUT (Data,Var,Abs) - - 0x09, 0x06, // USAGE (Vendor) address - 0x75, 0x40, // REPORT_SIZE (64) - 0x95, 0x01, // REPORT_COUNT (1) - 0x91, 0x02, // OUTPUT (Data,Var,Abs) - - 0x85,HID_ID_HIDCMD, // Report ID - 0x09, 0x01, // USAGE (Vendor) - 0x15, 0x00, // LOGICAL_MINIMUM (0) - 0x26, 0x04, 0x00, // Logical Maximum 4 - 0x75, 0x08, // REPORT_SIZE (8) - 0x95, 0x01, // REPORT_COUNT (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - - 0x09, 0x02, // USAGE (Vendor) class address - 0x75, 0x10, // REPORT_SIZE (16) - 0x95, 0x01, // REPORT_COUNT (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - - 0x09, 0x03, // USAGE (Vendor) class instance - 0x75, 0x08, // REPORT_SIZE (8) - 0x95, 0x01, // REPORT_COUNT (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - - 0x09, 0x04, // USAGE (Vendor) cmd - 0x75, 0x20, // REPORT_SIZE (32) - 0x95, 0x01, // REPORT_COUNT (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - - 0x09, 0x05, // USAGE (Vendor) - 0x75, 0x40, // REPORT_SIZE (64) value - 0x95, 0x01, // REPORT_COUNT (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - - 0x09, 0x06, // USAGE (Vendor) address - 0x75, 0x40, // REPORT_SIZE (64) - 0x95, 0x01, // REPORT_COUNT (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - - - - 0xc0, // END_COLLECTION - - - // BEGIN PID effects - 0x05,0x0F, // Usage Page Physical Interface - 0x09,0x92, // Usage PID State report - 0xA1,0x02, // Collection Datalink (logical) - 0x85,HID_ID_STATE+FFB_ID_OFFSET, // Report ID 2 - -// 0x09,0x22, // Usage Effect Block Index -// 0x15,0x01, // Logical Minimum 1 -// 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) -// 0x35,0x01, // Physical Minimum 1 -// 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) -// 0x75,0x08, // Report Size 8 -// 0x95,0x01, // Report Count 1 +// 0x15,0x00, // Logical Minimum 0 +// 0x25,0x01, // Logical Maximum 1 +// 0x35,0x00, // Physical Minimum 0 +// 0x45,0x01, // Physical Maximum 1 +// 0x75,0x01, // Report Size 1 +// 0x95,0x05, // Report Count 4 // 0x81,0x02, // Input (Variable) - - - - 0x09,0x9F, // Usage Device is Pause - 0x09,0xA0, // Usage Actuators Enabled - 0x09,0xA4, // Usage Safety Switch - 0x09,0xA6, // Usage Actuator Power - - 0x09,0x94, // Usage Effect Playing - /* - 0x15,0x00, // Logical Minimum 0 - 0x25,0x01, // Logical Maximum 1 - 0x35,0x00, // Physical Minimum 0 - 0x45,0x01, // Physical Maximum 1 - 0x75,0x01, // Report Size 1 - 0x95,0x01, // Report Count 1 - 0x81,0x02, // Input (Variable)*/ //14 - - 0x15,0x00, // Logical Minimum 0 - 0x25,0x01, // Logical Maximum 1 - 0x35,0x00, // Physical Minimum 0 - 0x45,0x01, // Physical Maximum 1 - 0x75,0x01, // Report Size 1 - 0x95,0x05, // Report Count 4 - 0x81,0x02, // Input (Variable) - 0x95,0x03, // Report Count 3 - 0x81,0x03, // Input (Constant, Variable) - 0xC0 , // End Collection - +// 0x95,0x03, // Report Count 3 +// 0x81,0x03, // Input (Constant, Variable) +// 0xC0 , // End Collection + HIDDESC_FFB_STATEREP, /* Output Collection Datalink: @@ -228,71 +113,72 @@ __ALIGN_BEGIN const uint8_t hid_2ffb_desc[USB_HID_2FFB_REPORT_DESC_SIZE] __ALIGN 12 effect types, 8bit each */ - 0x09,0x21, // Usage Set Effect Report - 0xA1,0x02, // Collection Datalink (Logical) - 0x85,HID_ID_EFFREP+FFB_ID_OFFSET, // Report ID 1 - 0x09,0x22, // Usage Effect Block Index - 0x15,0x01, // Logical Minimum 1 - 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) - 0x35,0x01, // Physical Minimum 1 - 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0x09,0x25, // Usage Effect Type - 0xA1,0x02, // Collection Datalink - 0x09, HID_USAGE_CONST, // Usage ET Constant Force - 0x09, HID_USAGE_RAMP, // Usage ET Ramp - 0x09, HID_USAGE_SQUR, // Usage ET Square - 0x09, HID_USAGE_SINE, // Usage ET Sine - 0x09, HID_USAGE_TRNG, // Usage ET Triangle - 0x09, HID_USAGE_STUP, // Usage ET Sawtooth Up - 0x09, HID_USAGE_STDN, // Usage ET Sawtooth Down - 0x09, HID_USAGE_SPRNG, // Usage ET Spring - 0x09, HID_USAGE_DMPR, // Usage ET Damper - 0x09, HID_USAGE_INRT, // Usage ET Inertia - 0x09, HID_USAGE_FRIC, // Usage ET Friction - // 0x09, 0x28, // Usage ET Custom Force Data - 0x25,0x0B, // Logical Maximum Bh (11d) - 0x15,0x01, // Logical Minimum 1 - 0x35,0x01, // Physical Minimum 1 - 0x45,0x0B, // Physical Maximum Bh (11d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x00, // Output - 0xC0 , // End Collection - 0x09,0x50, // Usage Duration - 0x09,0x54, // Usage Trigger Repeat Interval - 0x09,0x51, // Usage Sample Period - 0x09,0xA7, // Usage Start Delay - 0x15,0x00, // Logical Minimum 0 - 0x26,0xFF,0x7F, // Logical Maximum 7FFFh (32767d) - 0x35,0x00, // Physical Minimum 0 - 0x46,0xFF,0x7F, // Physical Maximum 7FFFh (32767d) - 0x66,0x03,0x10, // Unit 1003h (4099d) - 0x55,0xFD, // Unit Exponent FDh (253d) - 0x75,0x10, // Report Size 10h (16d) - 0x95,0x04, // Report Count 4 - 0x91,0x02, // Output (Variable) - 0x55,0x00, // Unit Exponent 0 - 0x66,0x00,0x00, // Unit 0 - 0x09,0x52, // Usage Gain - 0x15,0x00, // Logical Minimum 0 - 0x26,0xFF,0x00, // Logical Maximum FFh (255d) // TODO scaling? - 0x35,0x00, // Physical Minimum 0 - 0x46,0x10,0x27, // Physical Maximum 2710h (10000d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0x09,0x53, // Usage Trigger Button - 0x15,0x01, // Logical Minimum 1 - 0x25,0x08, // Logical Maximum 8 - 0x35,0x01, // Physical Minimum 1 - 0x45,0x08, // Physical Maximum 8 - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - + HIDDESC_FFB_SETEFREP, +// 0x09,0x21, // Usage Set Effect Report +// 0xA1,0x02, // Collection Datalink (Logical) +// 0x85,HID_ID_EFFREP+FFB_ID_OFFSET, // Report ID 1 +// 0x09,0x22, // Usage Effect Block Index +// 0x15,0x01, // Logical Minimum 1 +// 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) +// 0x35,0x01, // Physical Minimum 1 +// 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) +// 0x75,0x08, // Report Size 8 +// 0x95,0x01, // Report Count 1 +// 0x91,0x02, // Output (Variable) +// 0x09,0x25, // Usage Effect Type +// 0xA1,0x02, // Collection Datalink +// 0x09, HID_USAGE_CONST, // Usage ET Constant Force +// 0x09, HID_USAGE_RAMP, // Usage ET Ramp +// 0x09, HID_USAGE_SQUR, // Usage ET Square +// 0x09, HID_USAGE_SINE, // Usage ET Sine +// 0x09, HID_USAGE_TRNG, // Usage ET Triangle +// 0x09, HID_USAGE_STUP, // Usage ET Sawtooth Up +// 0x09, HID_USAGE_STDN, // Usage ET Sawtooth Down +// 0x09, HID_USAGE_SPRNG, // Usage ET Spring +// 0x09, HID_USAGE_DMPR, // Usage ET Damper +// 0x09, HID_USAGE_INRT, // Usage ET Inertia +// 0x09, HID_USAGE_FRIC, // Usage ET Friction +// // 0x09, 0x28, // Usage ET Custom Force Data +// 0x25,0x0B, // Logical Maximum Bh (11d) +// 0x15,0x01, // Logical Minimum 1 +// 0x35,0x01, // Physical Minimum 1 +// 0x45,0x0B, // Physical Maximum Bh (11d) +// 0x75,0x08, // Report Size 8 +// 0x95,0x01, // Report Count 1 +// 0x91,0x00, // Output +// 0xC0 , // End Collection +// 0x09,0x50, // Usage Duration +// 0x09,0x54, // Usage Trigger Repeat Interval +// 0x09,0x51, // Usage Sample Period +// 0x09,0xA7, // Usage Start Delay +// 0x15,0x00, // Logical Minimum 0 +// 0x26,0xFF,0x7F, // Logical Maximum 7FFFh (32767d) +// 0x35,0x00, // Physical Minimum 0 +// 0x46,0xFF,0x7F, // Physical Maximum 7FFFh (32767d) +// 0x66,0x03,0x10, // Unit 1003h (4099d) +// 0x55,0xFD, // Unit Exponent FDh (253d) +// 0x75,0x10, // Report Size 10h (16d) +// 0x95,0x04, // Report Count 4 +// 0x91,0x02, // Output (Variable) +// 0x55,0x00, // Unit Exponent 0 +// 0x66,0x00,0x00, // Unit 0 +// 0x09,0x52, // Usage Gain +// 0x15,0x00, // Logical Minimum 0 +// 0x26,0xFF,0x00, // Logical Maximum FFh (255d) // TODO scaling? +// 0x35,0x00, // Physical Minimum 0 +// 0x46,0x10,0x27, // Physical Maximum 2710h (10000d) +// 0x75,0x08, // Report Size 8 +// 0x95,0x01, // Report Count 1 +// 0x91,0x02, // Output (Variable) +// 0x09,0x53, // Usage Trigger Button +// 0x15,0x01, // Logical Minimum 1 +// 0x25,0x08, // Logical Maximum 8 +// 0x35,0x01, // Physical Minimum 1 +// 0x45,0x08, // Physical Maximum 8 +// 0x75,0x08, // Report Size 8 +// 0x95,0x01, // Report Count 1 +// 0x91,0x02, // Output (Variable) +// Len 108 bytes following 0x09,0x55, // Usage Axes Enable TODO multi axis 0xA1,0x02, // Collection Datalink 0x05,0x01, // Usage Page Generic Desktop @@ -344,39 +230,44 @@ __ALIGN_BEGIN const uint8_t hid_2ffb_desc[USB_HID_2FFB_REPORT_DESC_SIZE] __ALIGN 0xC0, // END_COLLECTION 0xC0, // END_COLLECTION - // Envelope Report Definition - 0x09,0x5A, // Usage Set Envelope Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_ENVREP+FFB_ID_OFFSET, // Report ID 2 - 0x09,0x22, // Usage Effect Block Index - 0x15,0x01, // Logical Minimum 1 - 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) - 0x35,0x01, // Physical Minimum 1 - 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0x09,0x5B, // Usage Attack Level - 0x09,0x5D, // Usage Fade Level - 0x16,0x00,0x00, // Logical Minimum 0 - 0x26,0xFF,0x7F, // Logical Maximum 7FFFh (32767d) - 0x36,0x00,0x00, // Physical Minimum 0 - 0x46,0xFF,0x7F, // Physical Maximum 7FFFh (32767d) - 0x75,0x10, // Report Size 16 - 0x95,0x02, // Report Count 2 - 0x91,0x02, // Output (Variable) - 0x09, 0x5C, // Usage Attack Time - 0x09, 0x5E, // Usage Fade Time - 0x66, 0x03, 0x10, // Unit 1003h (English Linear, Seconds) - 0x55, 0xFD, // Unit Exponent FDh (X10^-3 ==> Milisecond) - 0x27, 0xFF, 0x7F, 0x00, 0x00, // Logical Maximum FFFFFFFFh (4294967295) - 0x47, 0xFF, 0x7F, 0x00, 0x00, // Physical Maximum FFFFFFFFh (4294967295) - 0x75, 0x20, // Report Size 20h (32d) - 0x91, 0x02, // Output (Variable) - 0x45, 0x00, // Physical Maximum 0 - 0x66,0x00,0x00, // Unit 0 - 0x55,0x00, // Unit Exponent 0 - 0xC0 , // End Collection + HIDDESC_FFB_SETENVREP, +// // Envelope Report Definition +// 0x09,0x5A, // Usage Set Envelope Report +// 0xA1,0x02, // Collection Datalink +// 0x85,HID_ID_ENVREP+FFB_ID_OFFSET, // Report ID 2 +// 0x09,0x22, // Usage Effect Block Index +// 0x15,0x01, // Logical Minimum 1 +// 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) +// 0x35,0x01, // Physical Minimum 1 +// 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) +// 0x75,0x08, // Report Size 8 +// 0x95,0x01, // Report Count 1 +// 0x91,0x02, // Output (Variable) +// 0x09,0x5B, // Usage Attack Level +// 0x09,0x5D, // Usage Fade Level +// 0x16,0x00,0x00, // Logical Minimum 0 +// 0x26,0xFF,0x7F, // Logical Maximum 7FFFh (32767d) +// 0x36,0x00,0x00, // Physical Minimum 0 +// 0x46,0xFF,0x7F, // Physical Maximum 7FFFh (32767d) +// 0x75,0x10, // Report Size 16 +// 0x95,0x02, // Report Count 2 +// 0x91,0x02, // Output (Variable) +// 0x09, 0x5C, // Usage Attack Time +// 0x09, 0x5E, // Usage Fade Time +// 0x66, 0x03, 0x10, // Unit 1003h (English Linear, Seconds) +// 0x55, 0xFD, // Unit Exponent FDh (X10^-3 ==> Milisecond) +// 0x27, 0xFF, 0x7F, 0x00, 0x00, // Logical Maximum FFFFFFFFh (4294967295) +// 0x47, 0xFF, 0x7F, 0x00, 0x00, // Physical Maximum FFFFFFFFh (4294967295) +// 0x75, 0x20, // Report Size 20h (32d) +// 0x91, 0x02, // Output (Variable) +// 0x45, 0x00, // Physical Maximum 0 +// 0x66,0x00,0x00, // Unit 0 +// 0x55,0x00, // Unit Exponent 0 +// 0xC0 , // End Collection +// HIDDESC_FFB_SETCONDREP, + + // Condition report depends on ffb axis count + // 125 bytes following 0x09,0x5F, // Usage Set Condition Report 0xA1,0x02, // Collection Datalink 0x85,HID_ID_CONDREP+FFB_ID_OFFSET, // Report ID 3 @@ -433,102 +324,62 @@ __ALIGN_BEGIN const uint8_t hid_2ffb_desc[USB_HID_2FFB_REPORT_DESC_SIZE] __ALIGN 0x95,0x01, // Report Count 1 0x91,0x02, // Output (Variable) 0xC0 , // End Collection - 0x09,0x6E, // Usage Set Periodic Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_PRIDREP+FFB_ID_OFFSET, // Report ID 4 - 0x09,0x22, // Usage Effect Block Index - 0x15,0x01, // Logical Minimum 1 - 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) - 0x35,0x01, // Physical Minimum 1 - 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0x09,0x70, // Usage Magnitude - 0x16,0x00,0x00, // Logical Minimum 0 - 0x26,0xff, 0x7f, // Logical Maximum 7FFFh (32767d) - 0x36,0x00,0x00, // Physical Minimum 0 - 0x26,0xff, 0x7f, // Logical Maximum 7FFFh (32767d) - 0x75,0x10, // Report Size 16 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0x09, 0x6F, // Usage Offset - 0x16,0x00, 0x80, // Logical Minimum 7FFFh (-32767d) - 0x26,0xff, 0x7f, // Logical Maximum 7FFFh (32767d) - 0x36,0x00, 0x80, // Physical Minimum 7FFFh (-32767d) - 0x46,0xff, 0x7f, // Physical Maximum 7FFFh (32767d) - 0x95, 0x01, // Report Count 1 - 0x75, 0x10, // Report Size 16 - 0x91, 0x02, // Output (Variable) - 0x09, 0x71, // Usage Phase - 0x66, 0x14, 0x00, // Unit 14h (Eng Rotation, Degrees) - 0x55, 0xFE, // Unit Exponent FEh (X10^-2) - 0x15, 0x00, // Logical Minimum 0 - 0x27, 0x9F, 0x8C, 0x00, 0x00, // Logical Maximum 8C9Fh (35999d) - 0x35, 0x00, // Physical Minimum 0 - 0x47, 0x9F, 0x8C, 0x00, 0x00, // Physical Maximum 8C9Fh (35999d) - 0x75, 0x10, // Report Size 16 - 0x95, 0x01, // Report Count 1 - 0x91, 0x02, // Output (Variable) - 0x09, 0x72, // Usage Period - 0x15, 0x01, // Logical Minimum 1 - 0x27, 0xFF, 0x7F, 0x00, 0x00, // Logical Maximum 7FFFh (32K) - 0x35, 0x01, // Physical Minimum 1 - 0x47, 0xFF, 0x7F, 0x00, 0x00, // Physical Maximum 7FFFh (32K) - 0x66, 0x03, 0x10, // Unit 1003h (English Linear, Seconds) - 0x55, 0xFD, // Unit Exponent FDh (X10^-3 ==> Milisecond) - 0x75, 0x20, // Report Size 20h (32) - 0x95, 0x01, // Report Count 1 - 0x91, 0x02, // Output (Variable) - 0x66, 0x00, 0x00, // Unit 0 - 0x55,0x00, // Unit Exponent 0 - 0xC0 , // End Collection - 0x09,0x73, // Usage Set Constant Force Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_CONSTREP+FFB_ID_OFFSET, // Report ID 5 - 0x09,0x22, // Usage Effect Block Index - 0x15,0x01, // Logical Minimum 1 - 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) - 0x35,0x01, // Physical Minimum 1 - 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0x09,0x70, // Usage Magnitude - 0x16,0x00, 0x80, // Logical Minimum 7FFFh (-32767d) - 0x26,0xff, 0x7f, // Logical Maximum 7FFFh (32767d) - 0x36,0x00, 0x80, // Physical Minimum 7FFFh (-32767d) - 0x46,0xff, 0x7f, // Physical Maximum 7FFFh (32767d) - 0x75, 0x10, // Report Size 10h (16d) - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0xC0 , // End Collection - 0x09,0x74, // Usage Set Ramp Force Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_RAMPREP+FFB_ID_OFFSET, // Report ID 6 - 0x09,0x22, // Usage Effect Block Index - 0x15,0x01, // Logical Minimum 1 - 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) - 0x35,0x01, // Physical Minimum 1 - 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0x09,0x75, // Usage Ramp Start - 0x09,0x76, // Usage Ramp End - 0x16,0x00, 0x80, // Logical Minimum 7FFFh (-32767d) - 0x26,0xff, 0x7f, // Logical Maximum 7FFFh (32767d) - 0x36,0x00, 0x80, // Physical Minimum 7FFFh (-32767d) - 0x46,0xff, 0x7f, // Physical Maximum 7FFFh (32767d) - 0x75,0x10, // Report Size 16 - 0x95,0x02, // Report Count 2 - 0x91,0x02, // Output (Variable) - 0xC0 , // End Collection - -// 0x09,0x68, // Usage Custom Force Data Report + HIDDESC_FFB_SETPERIODICREP, +// 0x09,0x6E, // Usage Set Periodic Report +// 0xA1,0x02, // Collection Datalink +// 0x85,HID_ID_PRIDREP+FFB_ID_OFFSET, // Report ID 4 +// 0x09,0x22, // Usage Effect Block Index +// 0x15,0x01, // Logical Minimum 1 +// 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) +// 0x35,0x01, // Physical Minimum 1 +// 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) +// 0x75,0x08, // Report Size 8 +// 0x95,0x01, // Report Count 1 +// 0x91,0x02, // Output (Variable) +// 0x09,0x70, // Usage Magnitude +// 0x16,0x00,0x00, // Logical Minimum 0 +// 0x26,0xff, 0x7f, // Logical Maximum 7FFFh (32767d) +// 0x36,0x00,0x00, // Physical Minimum 0 +// 0x26,0xff, 0x7f, // Logical Maximum 7FFFh (32767d) +// 0x75,0x10, // Report Size 16 +// 0x95,0x01, // Report Count 1 +// 0x91,0x02, // Output (Variable) +// 0x09, 0x6F, // Usage Offset +// 0x16,0x00, 0x80, // Logical Minimum 7FFFh (-32767d) +// 0x26,0xff, 0x7f, // Logical Maximum 7FFFh (32767d) +// 0x36,0x00, 0x80, // Physical Minimum 7FFFh (-32767d) +// 0x46,0xff, 0x7f, // Physical Maximum 7FFFh (32767d) +// 0x95, 0x01, // Report Count 1 +// 0x75, 0x10, // Report Size 16 +// 0x91, 0x02, // Output (Variable) +// 0x09, 0x71, // Usage Phase +// 0x66, 0x14, 0x00, // Unit 14h (Eng Rotation, Degrees) +// 0x55, 0xFE, // Unit Exponent FEh (X10^-2) +// 0x15, 0x00, // Logical Minimum 0 +// 0x27, 0x9F, 0x8C, 0x00, 0x00, // Logical Maximum 8C9Fh (35999d) +// 0x35, 0x00, // Physical Minimum 0 +// 0x47, 0x9F, 0x8C, 0x00, 0x00, // Physical Maximum 8C9Fh (35999d) +// 0x75, 0x10, // Report Size 16 +// 0x95, 0x01, // Report Count 1 +// 0x91, 0x02, // Output (Variable) +// 0x09, 0x72, // Usage Period +// 0x15, 0x01, // Logical Minimum 1 +// 0x27, 0xFF, 0x7F, 0x00, 0x00, // Logical Maximum 7FFFh (32K) +// 0x35, 0x01, // Physical Minimum 1 +// 0x47, 0xFF, 0x7F, 0x00, 0x00, // Physical Maximum 7FFFh (32K) +// 0x66, 0x03, 0x10, // Unit 1003h (English Linear, Seconds) +// 0x55, 0xFD, // Unit Exponent FDh (X10^-3 ==> Milisecond) +// 0x75, 0x20, // Report Size 20h (32) +// 0x95, 0x01, // Report Count 1 +// 0x91, 0x02, // Output (Variable) +// 0x66, 0x00, 0x00, // Unit 0 +// 0x55,0x00, // Unit Exponent 0 +// 0xC0 , // End Collection + HIDDESC_FFB_SETCFREP, +// 0x09,0x73, // Usage Set Constant Force Report // 0xA1,0x02, // Collection Datalink -// 0x85,HID_ID_CSTMREP+FFB_ID_OFFSET, // Report ID 7 +// 0x85,HID_ID_CONSTREP+FFB_ID_OFFSET, // Report ID 5 // 0x09,0x22, // Usage Effect Block Index // 0x15,0x01, // Logical Minimum 1 // 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) @@ -537,119 +388,19 @@ __ALIGN_BEGIN const uint8_t hid_2ffb_desc[USB_HID_2FFB_REPORT_DESC_SIZE] __ALIGN // 0x75,0x08, // Report Size 8 // 0x95,0x01, // Report Count 1 // 0x91,0x02, // Output (Variable) -// 0x09,0x6C, // Usage Custom Force Data Offset -// 0x15,0x00, // Logical Minimum 0 -// 0x26,0x10,0x27, // Logical Maximum 2710h (10000d) -// 0x35,0x00, // Physical Minimum 0 -// 0x46,0x10,0x27, // Physical Maximum 2710h (10000d) -// 0x75,0x10, // Report Size 10h (16d) +// 0x09,0x70, // Usage Magnitude +// 0x16,0x00, 0x80, // Logical Minimum 7FFFh (-32767d) +// 0x26,0xff, 0x7f, // Logical Maximum 7FFFh (32767d) +// 0x36,0x00, 0x80, // Physical Minimum 7FFFh (-32767d) +// 0x46,0xff, 0x7f, // Physical Maximum 7FFFh (32767d) +// 0x75, 0x10, // Report Size 10h (16d) // 0x95,0x01, // Report Count 1 // 0x91,0x02, // Output (Variable) -// 0x09,0x69, // Usage Custom Force Data -// 0x15,0x81, // Logical Minimum 81h (-127d) -// 0x25,0x7F, // Logical Maximum 7Fh (127d) -// 0x35,0x00, // Physical Minimum 0 -// 0x46,0xFF,0x00, // Physical Maximum FFh (255d) -// 0x75,0x08, // Report Size 8 -// 0x95,0x0C, // Report Count Ch (12d) -// 0x92,0x02,0x01, // Output (Variable, Buffered) // 0xC0 , // End Collection -// 0x09,0x66, // Usage Download Force Sample -// 0xA1,0x02, // Collection Datalink -// 0x85,HID_ID_SMPLREP+FFB_ID_OFFSET, // Report ID 8 -// 0x05,0x01, // Usage Page Generic Desktop -// 0x09,0x30, // Usage X -// 0x09,0x31, // Usage Y -// 0x15,0x81, // Logical Minimum 81h (-127d) -// 0x25,0x7F, // Logical Maximum 7Fh (127d) -// 0x35,0x00, // Physical Minimum 0 -// 0x46,0xFF,0x00, // Physical Maximum FFh (255d) -// 0x75,0x08, // Report Size 8 -// 0x95,0x02, // Report Count 2 -// 0x91,0x02, // Output (Variable) -// 0xC0 , // End Collection - - 0x05,0x0F, // Usage Page Physical Interface - 0x09,0x77, // Usage Effect Operation Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_EFOPREP+FFB_ID_OFFSET, // Report ID Ah (10d) - 0x09,0x22, // Usage Effect Block Index - 0x15,0x01, // Logical Minimum 1 - 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) - 0x35,0x01, // Physical Minimum 1 - 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0x09,0x78, // Usage Effect Operation - 0xA1,0x02, // Collection Datalink - 0x09,0x79, // Usage Op Effect Start - 0x09,0x7A, // Usage Op Effect Start Solo - 0x09,0x7B, // Usage Op Effect Stop - 0x15,0x01, // Logical Minimum 1 - 0x25,0x03, // Logical Maximum 3 - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x00, // Output - 0xC0 , // End Collection - 0x09,0x7C, // Usage Loop Count - 0x15,0x00, // Logical Minimum 0 - 0x26,0xFF,0x00, // Logical Maximum FFh (255d) - 0x35,0x00, // Physical Minimum 0 - 0x46,0xFF,0x00, // Physical Maximum FFh (255d) - 0x91,0x02, // Output (Variable) - 0xC0 , // End Collection - 0x09,0x90, // Usage PID Block Free Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_BLKFRREP+FFB_ID_OFFSET, // Report ID Bh (11d) - 0x09,0x22, // Usage Effect Block Index - 0x15,0x01, // Logical Minimum 1 - 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) - 0x35,0x01, // Physical Minimum 1 - 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0xC0 , // End Collection - - 0x09,0x95, // Usage PID Device Control (0x96?) - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_CTRLREP+FFB_ID_OFFSET, // Report ID Ch (12d) - 0x09,0x96, // Usage PID Device Control (0x96?) - 0xA1,0x02, // Collection Datalink - - 0x09,0x97, // Usage DC Enable Actuators - 0x09,0x98, // Usage DC Disable Actuators - 0x09,0x99, // Usage DC Stop All Effects - 0x09,0x9A, // Usage DC Device Reset - 0x09,0x9B, // Usage DC Device Pause - 0x09,0x9C, // Usage DC Device Continue - - - - 0x15,0x01, // Logical Minimum 1 - 0x25,0x06, // Logical Maximum 6 - 0x75,0x01, // Report Size 1 - 0x95,0x08, // Report Count 8 - 0x91,0x02, // Output - - 0xC0 , // End Collection - 0xC0 , // End Collection - 0x09,0x7D, // Usage Device Gain Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_GAINREP+FFB_ID_OFFSET, // Report ID Dh (13d) - 0x09,0x7E, // Usage Device Gain - 0x15,0x00, // Logical Minimum 0 - 0x26,0xFF,0x00, // Logical Maximum FFh (255d) - 0x35,0x00, // Physical Minimum 0 - 0x46,0x10,0x27, // Physical Maximum 2710h (10000d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0x91,0x02, // Output (Variable) - 0xC0 , // End Collection -// 0x09,0x6B, // Usage Set Custom Force Report + HIDDESC_FFB_SETRAMPREP, +// 0x09,0x74, // Usage Set Ramp Force Report // 0xA1,0x02, // Collection Datalink -// 0x85,HID_ID_SETCREP+FFB_ID_OFFSET, // Report ID Eh (14d) +// 0x85,HID_ID_RAMPREP+FFB_ID_OFFSET, // Report ID 6 // 0x09,0x22, // Usage Effect Block Index // 0x15,0x01, // Logical Minimum 1 // 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) @@ -658,131 +409,442 @@ __ALIGN_BEGIN const uint8_t hid_2ffb_desc[USB_HID_2FFB_REPORT_DESC_SIZE] __ALIGN // 0x75,0x08, // Report Size 8 // 0x95,0x01, // Report Count 1 // 0x91,0x02, // Output (Variable) -// 0x09,0x6D, // Usage Sample Count +// 0x09,0x75, // Usage Ramp Start +// 0x09,0x76, // Usage Ramp End +// 0x16,0x00, 0x80, // Logical Minimum 7FFFh (-32767d) +// 0x26,0xff, 0x7f, // Logical Maximum 7FFFh (32767d) +// 0x36,0x00, 0x80, // Physical Minimum 7FFFh (-32767d) +// 0x46,0xff, 0x7f, // Physical Maximum 7FFFh (32767d) +// 0x75,0x10, // Report Size 16 +// 0x95,0x02, // Report Count 2 +// 0x91,0x02, // Output (Variable) +// 0xC0 , // End Collection +// +// +//// 0x09,0x68, // Usage Custom Force Data Report +//// 0xA1,0x02, // Collection Datalink +//// 0x85,HID_ID_CSTMREP+FFB_ID_OFFSET, // Report ID 7 +//// 0x09,0x22, // Usage Effect Block Index +//// 0x15,0x01, // Logical Minimum 1 +//// 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) +//// 0x35,0x01, // Physical Minimum 1 +//// 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) +//// 0x75,0x08, // Report Size 8 +//// 0x95,0x01, // Report Count 1 +//// 0x91,0x02, // Output (Variable) +//// 0x09,0x6C, // Usage Custom Force Data Offset +//// 0x15,0x00, // Logical Minimum 0 +//// 0x26,0x10,0x27, // Logical Maximum 2710h (10000d) +//// 0x35,0x00, // Physical Minimum 0 +//// 0x46,0x10,0x27, // Physical Maximum 2710h (10000d) +//// 0x75,0x10, // Report Size 10h (16d) +//// 0x95,0x01, // Report Count 1 +//// 0x91,0x02, // Output (Variable) +//// 0x09,0x69, // Usage Custom Force Data +//// 0x15,0x81, // Logical Minimum 81h (-127d) +//// 0x25,0x7F, // Logical Maximum 7Fh (127d) +//// 0x35,0x00, // Physical Minimum 0 +//// 0x46,0xFF,0x00, // Physical Maximum FFh (255d) +//// 0x75,0x08, // Report Size 8 +//// 0x95,0x0C, // Report Count Ch (12d) +//// 0x92,0x02,0x01, // Output (Variable, Buffered) +//// 0xC0 , // End Collection +//// 0x09,0x66, // Usage Download Force Sample +//// 0xA1,0x02, // Collection Datalink +//// 0x85,HID_ID_SMPLREP+FFB_ID_OFFSET, // Report ID 8 +//// 0x05,0x01, // Usage Page Generic Desktop +//// 0x09,0x30, // Usage X +//// 0x09,0x31, // Usage Y +//// 0x15,0x81, // Logical Minimum 81h (-127d) +//// 0x25,0x7F, // Logical Maximum 7Fh (127d) +//// 0x35,0x00, // Physical Minimum 0 +//// 0x46,0xFF,0x00, // Physical Maximum FFh (255d) +//// 0x75,0x08, // Report Size 8 +//// 0x95,0x02, // Report Count 2 +//// 0x91,0x02, // Output (Variable) +//// 0xC0 , // End Collection + HIDDESC_FFB_EFOPREP, +// 0x05,0x0F, // Usage Page Physical Interface +// 0x09,0x77, // Usage Effect Operation Report +// 0xA1,0x02, // Collection Datalink +// 0x85,HID_ID_EFOPREP+FFB_ID_OFFSET, // Report ID Ah (10d) +// 0x09,0x22, // Usage Effect Block Index +// 0x15,0x01, // Logical Minimum 1 +// 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) +// 0x35,0x01, // Physical Minimum 1 +// 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) +// 0x75,0x08, // Report Size 8 +// 0x95,0x01, // Report Count 1 +// 0x91,0x02, // Output (Variable) +// 0x09,0x78, // Usage Effect Operation +// 0xA1,0x02, // Collection Datalink +// 0x09,0x79, // Usage Op Effect Start +// 0x09,0x7A, // Usage Op Effect Start Solo +// 0x09,0x7B, // Usage Op Effect Stop +// 0x15,0x01, // Logical Minimum 1 +// 0x25,0x03, // Logical Maximum 3 +// 0x75,0x08, // Report Size 8 +// 0x95,0x01, // Report Count 1 +// 0x91,0x00, // Output +// 0xC0 , // End Collection +// 0x09,0x7C, // Usage Loop Count // 0x15,0x00, // Logical Minimum 0 // 0x26,0xFF,0x00, // Logical Maximum FFh (255d) // 0x35,0x00, // Physical Minimum 0 // 0x46,0xFF,0x00, // Physical Maximum FFh (255d) -// 0x75,0x08, // Report Size 8 -// 0x95,0x01, // Report Count 1 // 0x91,0x02, // Output (Variable) -// 0x09,0x51, // Usage Sample Period -// 0x66,0x03,0x10, // Unit 1003h (4099d) -// 0x55,0xFD, // Unit Exponent FDh (253d) +// 0xC0 , // End Collection + HIDDESC_FFB_BLOCKFREEREP, +// 0x09,0x90, // Usage PID Block Free Report +// 0xA1,0x02, // Collection Datalink +// 0x85,HID_ID_BLKFRREP+FFB_ID_OFFSET, // Report ID Bh (11d) +// 0x09,0x22, // Usage Effect Block Index +// 0x15,0x01, // Logical Minimum 1 +// 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) +// 0x35,0x01, // Physical Minimum 1 +// 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) +// 0x75,0x08, // Report Size 8 +// 0x95,0x01, // Report Count 1 +// 0x91,0x02, // Output (Variable) +// 0xC0 , // End Collection + HIDDESC_FFB_DEVCTRLREP, +// 0x09,0x95, // Usage PID Device Control (0x96?) +// 0xA1,0x02, // Collection Datalink +// 0x85,HID_ID_CTRLREP+FFB_ID_OFFSET, // Report ID Ch (12d) +// 0x09,0x96, // Usage PID Device Control (0x96?) +// 0xA1,0x02, // Collection Datalink +// +// 0x09,0x97, // Usage DC Enable Actuators +// 0x09,0x98, // Usage DC Disable Actuators +// 0x09,0x99, // Usage DC Stop All Effects +// 0x09,0x9A, // Usage DC Device Reset +// 0x09,0x9B, // Usage DC Device Pause +// 0x09,0x9C, // Usage DC Device Continue +// +// +// +// 0x15,0x01, // Logical Minimum 1 +// 0x25,0x06, // Logical Maximum 6 +// 0x75,0x01, // Report Size 1 +// 0x95,0x08, // Report Count 8 +// 0x91,0x02, // Output +// +// 0xC0 , // End Collection +// 0xC0 , // End Collection +// 0x09,0x7D, // Usage Device Gain Report +// 0xA1,0x02, // Collection Datalink +// 0x85,HID_ID_GAINREP+FFB_ID_OFFSET, // Report ID Dh (13d) +// 0x09,0x7E, // Usage Device Gain // 0x15,0x00, // Logical Minimum 0 -// 0x26,0xFF,0x7F, // Logical Maximum 7FFFh (32767d) +// 0x26,0xFF,0x00, // Logical Maximum FFh (255d) // 0x35,0x00, // Physical Minimum 0 -// 0x46,0xFF,0x7F, // Physical Maximum 7FFFh (32767d) -// 0x75,0x10, // Report Size 10h (16d) +// 0x46,0x10,0x27, // Physical Maximum 2710h (10000d) +// 0x75,0x08, // Report Size 8 // 0x95,0x01, // Report Count 1 // 0x91,0x02, // Output (Variable) -// 0x55,0x00, // Unit Exponent 0 -// 0x66,0x00,0x00, // Unit 0 +// 0xC0 , // End Collection + +//// 0x09,0x6B, // Usage Set Custom Force Report +//// 0xA1,0x02, // Collection Datalink +//// 0x85,HID_ID_SETCREP+FFB_ID_OFFSET, // Report ID Eh (14d) +//// 0x09,0x22, // Usage Effect Block Index +//// 0x15,0x01, // Logical Minimum 1 +//// 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) +//// 0x35,0x01, // Physical Minimum 1 +//// 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) +//// 0x75,0x08, // Report Size 8 +//// 0x95,0x01, // Report Count 1 +//// 0x91,0x02, // Output (Variable) +//// 0x09,0x6D, // Usage Sample Count +//// 0x15,0x00, // Logical Minimum 0 +//// 0x26,0xFF,0x00, // Logical Maximum FFh (255d) +//// 0x35,0x00, // Physical Minimum 0 +//// 0x46,0xFF,0x00, // Physical Maximum FFh (255d) +//// 0x75,0x08, // Report Size 8 +//// 0x95,0x01, // Report Count 1 +//// 0x91,0x02, // Output (Variable) +//// 0x09,0x51, // Usage Sample Period +//// 0x66,0x03,0x10, // Unit 1003h (4099d) +//// 0x55,0xFD, // Unit Exponent FDh (253d) +//// 0x15,0x00, // Logical Minimum 0 +//// 0x26,0xFF,0x7F, // Logical Maximum 7FFFh (32767d) +//// 0x35,0x00, // Physical Minimum 0 +//// 0x46,0xFF,0x7F, // Physical Maximum 7FFFh (32767d) +//// 0x75,0x10, // Report Size 10h (16d) +//// 0x95,0x01, // Report Count 1 +//// 0x91,0x02, // Output (Variable) +//// 0x55,0x00, // Unit Exponent 0 +//// 0x66,0x00,0x00, // Unit 0 +//// 0xC0 , // End Collection + HIDDESC_FFB_NEWEFREP, +// 0x09,0xAB, // Usage Create New Effect Report +// 0xA1,0x02, // Collection Datalink +// 0x85,HID_ID_NEWEFREP+FFB_ID_OFFSET, // Report ID 1 +// 0x09,0x25, // Usage Effect Type +// 0xA1,0x02, // Collection Datalink +// 0x09, HID_USAGE_CONST, // Usage ET Constant Force +// 0x09, HID_USAGE_RAMP, // Usage ET Ramp +// 0x09, HID_USAGE_SQUR, // Usage ET Square +// 0x09, HID_USAGE_SINE, // Usage ET Sine +// 0x09, HID_USAGE_TRNG, // Usage ET Triangle +// 0x09, HID_USAGE_STUP, // Usage ET Sawtooth Up +// 0x09, HID_USAGE_STDN, // Usage ET Sawtooth Down +// 0x09, HID_USAGE_SPRNG, // Usage ET Spring +// 0x09, HID_USAGE_DMPR, // Usage ET Damper +// 0x09, HID_USAGE_INRT, // Usage ET Inertia +// 0x09, HID_USAGE_FRIC, // Usage ET Friction +//// 0x09, 0x28, // Usage ET Custom Force Data +// 0x25,0x0B, // Logical Maximum Ch (11d) +// 0x15,0x01, // Logical Minimum 1 +// 0x35,0x01, // Physical Minimum 1 +// 0x45,0x0B, // Physical Maximum Ch (11d) +// 0x75,0x08, // Report Size 8 +// 0x95,0x01, // Report Count 1 +// 0xB1,0x00, // Feature +// 0xC0 , // End Collection +// 0x05,0x01, // Usage Page Generic Desktop +// 0x09,0x3B, // Usage Reserved (Byte count) +// 0x15,0x00, // Logical Minimum 0 +// 0x26,0xFF,0x01, // Logical Maximum 1FFh (511d) +// 0x35,0x00, // Physical Minimum 0 +// 0x46,0xFF,0x01, // Physical Maximum 1FFh (511d) +// 0x75,0x0A, // Report Size Ah (10d) +// 0x95,0x01, // Report Count 1 +// 0xB1,0x02, // Feature (Variable) +// 0x75,0x06, // Report Size 6 +// 0xB1,0x01, // Feature (Constant) // 0xC0 , // End Collection - 0x09,0xAB, // Usage Create New Effect Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_NEWEFREP+FFB_ID_OFFSET, // Report ID 1 - 0x09,0x25, // Usage Effect Type +// 0x05,0x0F, // Usage Page Physical Interface + HIDDESC_FFB_BLOCKLOADREP, +// 0x09,0x89, // Usage Block Load Report +// 0xA1,0x02, // Collection Datalink +// 0x85,HID_ID_BLKLDREP+FFB_ID_OFFSET, // Report ID 0x12 +// 0x09,0x22, // Usage Effect Block Index +// 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) +// 0x15,0x01, // Logical Minimum 1 +// 0x35,0x01, // Physical Minimum 1 +// 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) +// 0x75,0x08, // Report Size 8 +// 0x95,0x01, // Report Count 1 +// 0xB1,0x02, // Feature (Variable) +// 0x09,0x8B, // Usage Block Load Status +// 0xA1,0x02, // Collection Datalink +// 0x09,0x8C, // Usage Block Load Success +// 0x09,0x8D, // Usage Block Load Full +// 0x09,0x8E, // Usage Block Load Error +// 0x15,0x01, // Logical Minimum 1 +// 0x25,0x03, // Logical Maximum 3 +// 0x35,0x01, // Physical Minimum 1 +// 0x45,0x03, // Physical Maximum 3 +// 0x75,0x08, // Report Size 8 +// 0x95,0x01, // Report Count 1 +// 0xB1,0x00, // Feature +// 0xC0 , // End Collection +// 0x09,0xAC, // Usage Pool available +// 0x15,0x00, // Logical Minimum 0 +// 0x27,0xFF,0xFF,0x00,0x00, // Logical Maximum FFFFh (65535d) +// 0x35,0x00, // Physical Minimum 0 +// 0x47,0xFF,0xFF,0x00,0x00, // Physical Maximum FFFFh (65535d) +// 0x75,0x10, // Report Size 10h (16d) +// 0x95,0x01, // Report Count 1 +// 0xB1,0x00, // Feature +// 0xC0 , // End Collection + HIDDESC_FFB_POOLREP, +// 0x09,0x7F, // Usage PID Pool Report +// 0xA1,0x02, // Collection Datalink +// 0x85,HID_ID_POOLREP+FFB_ID_OFFSET, // Report ID 0x13 +// 0x09,0x80, // Usage RAM Pool size +// 0x75,0x10, // Report Size 10h (16d) +// 0x95,0x01, // Report Count 1 +// 0x15,0x00, // Logical Minimum 0 +// 0x35,0x00, // Physical Minimum 0 +// 0x27,0xFF,0xFF,0x00,0x00, // Logical Maximum FFFFh (65535d) +// 0x47,0xFF,0xFF,0x00,0x00, // Physical Maximum FFFFh (65535d) +// 0xB1,0x02, // Feature (Variable) +// 0x09,0x83, // Usage Simultaneous Effects Max +// 0x26,0xFF,0x00, // Logical Maximum FFh (255d) +// 0x46,0xFF,0x00, // Physical Maximum FFh (255d) +// 0x75,0x08, // Report Size 8 +// 0x95,0x01, // Report Count 1 +// 0xB1,0x02, // Feature (Variable) +// 0x09,0xA9, // Usage Device Managed Pool +// 0x09,0xAA, // Usage Shared Parameter Blocks +// 0x75,0x01, // Report Size 1 +// 0x95,0x02, // Report Count 2 +// 0x15,0x00, // Logical Minimum 0 +// 0x25,0x01, // Logical Maximum 1 +// 0x35,0x00, // Physical Minimum 0 +// 0x45,0x01, // Physical Maximum 1 +// 0xB1,0x02, // Feature (Variable) +// 0x75,0x06, // Report Size 6 +// 0x95,0x01, // Report Count 1 +// 0xB1,0x03, // Feature (Constant, Variable) +// 0xC0, // End Collection + + 0xC0 /* END_COLLECTION */ +}; +#endif + +#ifdef AXIS2_FFB_HID_DESC_32B +__ALIGN_BEGIN const uint8_t hid_2ffb_desc_32b[USB_HID_2FFB_REPORT_DESC_32B_SIZE] __ALIGN_END = +{ + 0x05, 0x01, /* USAGE_PAGE (Generic Desktop)*/ + 0x09, 0x04, /* USAGE (Joystick)*/ + 0xa1, 0x01, /* COLLECTION (Application)*/ + HIDDESC_GAMEPAD_32B, + + HIDDESC_CTRL_REPORTS, // HID command report support + + HIDDESC_FFB_STATEREP, + /* + Output + Collection Datalink: + Usage Set Effect Report + + ID:1 + Effect Block Index: 8bit + + subcollection Effect Type + 12 effect types, 8bit each + + */ + HIDDESC_FFB_SETEFREP, + +// Len 108 bytes following + 0x09,0x55, // Usage Axes Enable TODO multi axis + 0xA1,0x02, // Collection Datalink + 0x05,0x01, // Usage Page Generic Desktop + 0x09,0x30, // Usage X + 0x09,0x31, // Usage Y + 0x15,0x00, // Logical Minimum 0 + 0x25,0x01, // Logical Maximum 1 + 0x75,0x01, // Report Size 1 + 0x95,0x02, // Report Count 2 + 0x91,0x02, // Output (Variable) + 0xC0 , // End Collection + 0x05,0x0F, // Usage Page Physical Interface + 0x09,0x56, // Usage Direction Enable + 0x95,0x01, // Report Count 1 + 0x91,0x02, // Output (Variable) + 0x95,0x05, // Report Count 5 + 0x91,0x03, // Output (Constant, Variable) + + 0x09,0x57, // Usage Direction 0xA1,0x02, // Collection Datalink - 0x09, HID_USAGE_CONST, // Usage ET Constant Force - 0x09, HID_USAGE_RAMP, // Usage ET Ramp - 0x09, HID_USAGE_SQUR, // Usage ET Square - 0x09, HID_USAGE_SINE, // Usage ET Sine - 0x09, HID_USAGE_TRNG, // Usage ET Triangle - 0x09, HID_USAGE_STUP, // Usage ET Sawtooth Up - 0x09, HID_USAGE_STDN, // Usage ET Sawtooth Down - 0x09, HID_USAGE_SPRNG, // Usage ET Spring - 0x09, HID_USAGE_DMPR, // Usage ET Damper - 0x09, HID_USAGE_INRT, // Usage ET Inertia - 0x09, HID_USAGE_FRIC, // Usage ET Friction -// 0x09, 0x28, // Usage ET Custom Force Data - 0x25,0x0B, // Logical Maximum Ch (11d) + 0x0B,0x01,0x00,0x0A,0x00, // Usage Ordinals: Instance 1 + 0x0B,0x02,0x00,0x0A,0x00, // Usage Ordinals: Instance 2 + 0x66,0x14,0x00, // Unit 14h (20d) Angular position + 0x55,0xFE, // Unit Exponent FEh (254d) +// 0x15,0x00, // Logical Minimum 0 +// 0x26,0xFF,0x00, // Logical Maximum FFh (255d) + 0x15,0x00, // Logical Minimum 0 + 0x27,0xA0,0x8C,0x00,0x00, // Logical Maximum 8CA0h (36000d) + 0x35,0x00, // Physical Minimum 0 + 0x47,0xA0,0x8C,0x00,0x00, // Physical Maximum 8CA0h (36000d) + 0x66,0x00,0x00, // Unit 0 + 0x75,0x10, // Report Size 16 +// 0x95,0x01, // Report Count 1 + 0x95,0x02, // Report Count 2 + 0x91,0x02, // Output (Variable) + 0x55,0x00, // Unit Exponent 0 + 0x66,0x00,0x00, // Unit 0 + 0xC0, // End Collection + + 0x05, 0x0F, // USAGE_PAGE (Physical Interface) + 0x09, 0x58, // USAGE (Type Specific Block Offset) + 0xA1, 0x02, // COLLECTION (Logical) + 0x0B, 0x01, 0x00, 0x0A, 0x00, //USAGE (Ordinals:Instance 1 + 0x0B, 0x02, 0x00, 0x0A, 0x00, //USAGE (Ordinals:Instance 2) + 0x26, 0xFD, 0x7F, // LOGICAL_MAXIMUM (32765) ; 32K RAM or ROM max. + 0x75, 0x10, // REPORT_SIZE (16) + 0x95, 0x02, // REPORT_COUNT (2) + 0x91, 0x02, // OUTPUT (Data,Var,Abs) + 0xC0, // END_COLLECTION + 0xC0, // END_COLLECTION + + HIDDESC_FFB_SETENVREP, + +// HIDDESC_FFB_SETCONDREP, + + // Condition report depends on ffb axis count + // 125 bytes following + 0x09,0x5F, // Usage Set Condition Report + 0xA1,0x02, // Collection Datalink + 0x85,HID_ID_CONDREP+FFB_ID_OFFSET, // Report ID 3 + 0x09,0x22, // Usage Effect Block Index 0x15,0x01, // Logical Minimum 1 + 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) 0x35,0x01, // Physical Minimum 1 - 0x45,0x0B, // Physical Maximum Ch (11d) + 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) 0x75,0x08, // Report Size 8 0x95,0x01, // Report Count 1 - 0xB1,0x00, // Feature - 0xC0 , // End Collection - 0x05,0x01, // Usage Page Generic Desktop - 0x09,0x3B, // Usage Reserved (Byte count) - 0x15,0x00, // Logical Minimum 0 - 0x26,0xFF,0x01, // Logical Maximum 1FFh (511d) - 0x35,0x00, // Physical Minimum 0 - 0x46,0xFF,0x01, // Physical Maximum 1FFh (511d) - 0x75,0x0A, // Report Size Ah (10d) - 0x95,0x01, // Report Count 1 - 0xB1,0x02, // Feature (Variable) - 0x75,0x06, // Report Size 6 - 0xB1,0x01, // Feature (Constant) - 0xC0 , // End Collection - 0x05,0x0F, // Usage Page Physical Interface - 0x09,0x89, // Usage Block Load Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_BLKLDREP+FFB_ID_OFFSET, // Report ID 0x12 - 0x09,0x22, // Usage Effect Block Index - 0x25,MAX_EFFECTS, // Logical Maximum 28h (40d) - 0x15,0x01, // Logical Minimum 1 - 0x35,0x01, // Physical Minimum 1 - 0x45,MAX_EFFECTS, // Physical Maximum 28h (40d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0xB1,0x02, // Feature (Variable) - 0x09,0x8B, // Usage Block Load Status - 0xA1,0x02, // Collection Datalink - 0x09,0x8C, // Usage Block Load Success - 0x09,0x8D, // Usage Block Load Full - 0x09,0x8E, // Usage Block Load Error - 0x15,0x01, // Logical Minimum 1 + 0x91,0x02, // Output (Variable) + 0x09,0x23, // Usage Parameter Block Offset + 0x15,0x00, // Logical Minimum 0 0x25,0x03, // Logical Maximum 3 - 0x35,0x01, // Physical Minimum 1 + 0x35,0x00, // Physical Minimum 0 0x45,0x03, // Physical Maximum 3 - 0x75,0x08, // Report Size 8 + 0x75,0x04, // Report Size 4 0x95,0x01, // Report Count 1 - 0xB1,0x00, // Feature - 0xC0 , // End Collection - 0x09,0xAC, // Usage Pool available - 0x15,0x00, // Logical Minimum 0 - 0x27,0xFF,0xFF,0x00,0x00, // Logical Maximum FFFFh (65535d) - 0x35,0x00, // Physical Minimum 0 - 0x47,0xFF,0xFF,0x00,0x00, // Physical Maximum FFFFh (65535d) - 0x75,0x10, // Report Size 10h (16d) - 0x95,0x01, // Report Count 1 - 0xB1,0x00, // Feature + 0x91,0x02, // Output (Variable) + 0x09,0x58, // Usage Type Specific Block Off... + 0xA1,0x02, // Collection Datalink + 0x0B,0x01,0x00,0x0A,0x00, // Usage Ordinals: Instance 1 + 0x0B,0x02,0x00,0x0A,0x00, // Usage Ordinals: Instance 2 + 0x75,0x02, // Report Size 2 + 0x95,0x02, // Report Count 2 + 0x91,0x02, // Output (Variable) + 0xC0 , // End Collection + 0x16,0x00, 0x80, // Logical Minimum 7FFFh (-32767d) + 0x26,0xff, 0x7f, // Logical Maximum 7FFFh (32767d) + 0x36,0x00, 0x80, // Physical Minimum 7FFFh (-32767d) + 0x46,0xff, 0x7f, // Physical Maximum 7FFFh (32767d) + + 0x09,0x60, // Usage CP Offset + 0x75,0x10, // Report Size 16 + 0x95,0x01, // Report Count 1 + 0x91,0x02, // Output (Variable) + 0x36,0x00, 0x80, // Physical Minimum (-32768) + 0x46,0xff, 0x7f, // Physical Maximum (32767) + 0x09,0x61, // Usage Positive Coefficient + 0x09,0x62, // Usage Negative Coefficient + 0x95,0x02, // Report Count 2 + 0x91,0x02, // Output (Variable) + 0x16,0x00,0x00, // Logical Minimum 0 + 0x26,0xff, 0x7f, // Logical Maximum (32767) + 0x36,0x00,0x00, // Physical Minimum 0 + 0x46,0xff, 0x7f, // Physical Maximum (32767) + 0x09,0x63, // Usage Positive Saturation + 0x09,0x64, // Usage Negative Saturation + 0x75,0x10, // Report Size 16 + 0x95,0x02, // Report Count 2 + 0x91,0x02, // Output (Variable) + 0x09,0x65, // Usage Dead Band + 0x46,0xff, 0x7f, // Physical Maximum (32767) + 0x95,0x01, // Report Count 1 + 0x91,0x02, // Output (Variable) 0xC0 , // End Collection - 0x09,0x7F, // Usage PID Pool Report - 0xA1,0x02, // Collection Datalink - 0x85,HID_ID_POOLREP+FFB_ID_OFFSET, // Report ID 0x13 - 0x09,0x80, // Usage RAM Pool size - 0x75,0x10, // Report Size 10h (16d) - 0x95,0x01, // Report Count 1 - 0x15,0x00, // Logical Minimum 0 - 0x35,0x00, // Physical Minimum 0 - 0x27,0xFF,0xFF,0x00,0x00, // Logical Maximum FFFFh (65535d) - 0x47,0xFF,0xFF,0x00,0x00, // Physical Maximum FFFFh (65535d) - 0xB1,0x02, // Feature (Variable) - 0x09,0x83, // Usage Simultaneous Effects Max - 0x26,0xFF,0x00, // Logical Maximum FFh (255d) - 0x46,0xFF,0x00, // Physical Maximum FFh (255d) - 0x75,0x08, // Report Size 8 - 0x95,0x01, // Report Count 1 - 0xB1,0x02, // Feature (Variable) - 0x09,0xA9, // Usage Device Managed Pool - 0x09,0xAA, // Usage Shared Parameter Blocks - 0x75,0x01, // Report Size 1 - 0x95,0x02, // Report Count 2 - 0x15,0x00, // Logical Minimum 0 - 0x25,0x01, // Logical Maximum 1 - 0x35,0x00, // Physical Minimum 0 - 0x45,0x01, // Physical Maximum 1 - 0xB1,0x02, // Feature (Variable) - 0x75,0x06, // Report Size 6 - 0x95,0x01, // Report Count 1 - 0xB1,0x03, // Feature (Constant, Variable) - 0xC0, // End Collection + HIDDESC_FFB_SETPERIODICREP, + + HIDDESC_FFB_SETCFREP, + + HIDDESC_FFB_SETRAMPREP, + + HIDDESC_FFB_EFOPREP, + + HIDDESC_FFB_BLOCKFREEREP, + + HIDDESC_FFB_DEVCTRLREP, + + HIDDESC_FFB_NEWEFREP, + + HIDDESC_FFB_BLOCKLOADREP, + + HIDDESC_FFB_POOLREP, 0xC0 /* END_COLLECTION */ }; - #endif + + diff --git a/Firmware/FFBoard/UserExtensions/Src/usb_hid_gamepad.c b/Firmware/FFBoard/UserExtensions/Src/usb_hid_gamepad.c index 474fd7bc5..bc56f3781 100644 --- a/Firmware/FFBoard/UserExtensions/Src/usb_hid_gamepad.c +++ b/Firmware/FFBoard/UserExtensions/Src/usb_hid_gamepad.c @@ -16,111 +16,31 @@ */ __ALIGN_BEGIN const uint8_t hid_gamepad_desc[USB_HID_GAMEPAD_REPORT_DESC_SIZE] __ALIGN_END = { - 0x05, 0x01, // USAGE_PAGE (Generic Desktop) - 0x09, 0x04, // USAGE (Joystick) - 0xa1, 0x01, // COLLECTION (Application) - 0xa1, 0x00, // COLLECTION (Physical) - 0x85, 0x01, // REPORT_ID (1) - 0x05, 0x09, // USAGE_PAGE (Button) - 0x19, 0x01, // USAGE_MINIMUM (Button 1) - 0x29, 0x40, // USAGE_MAXIMUM (Button 64) - 0x15, 0x00, // LOGICAL_MINIMUM (0) - 0x25, 0x01, // LOGICAL_MAXIMUM (1) - 0x95, 0x40, // REPORT_COUNT (64) - 0x75, 0x01, // REPORT_SIZE (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - 0x05, 0x01, // USAGE_PAGE (Generic Desktop) - 0x09, HID_USAGE_X, // USAGE (X) - 0x09, HID_USAGE_Y, // USAGE (Y) - 0x09, HID_USAGE_Z, // USAGE (Z) - 0x09, HID_USAGE_RX, // USAGE (Rx) - 0x09, HID_USAGE_RY, // USAGE (Ry) - 0x09, HID_USAGE_RZ, // USAGE (Rz) - 0x09, HID_USAGE_SL1, // USAGE (Dial) - 0x09, HID_USAGE_SL0, // USAGE (Slider) - 0x16, 0x01, 0x80, // LOGICAL_MINIMUM (-32767) - 0x26, 0xff, 0x7f, // LOGICAL_MAXIMUM (32767) - 0x75, 0x10, // REPORT_SIZE (16) - 0x95, 0x08, // REPORT_COUNT (8) - 0x81, 0x02, // INPUT (Data,Var,Abs) - 0xc0, // END_COLLECTION + 0x05, 0x01, /* USAGE_PAGE (Generic Desktop)*/ + 0x09, 0x04, /* USAGE (Joystick)*/ + 0xa1, 0x01, /* COLLECTION (Application)*/ + HIDDESC_GAMEPAD_16B, + HIDDESC_CTRL_REPORTS, // HID command report support - // Control reports - 0x06, 0x00, 0xFF, // USAGE_PAGE (Vendor) - 0x09, 0x00, // USAGE (Vendor) - 0xA1, 0x01, // Collection (Application) - - 0x85,HID_ID_HIDCMD, // Report ID - 0x09, 0x01, // USAGE (Vendor) - 0x15, 0x00, // LOGICAL_MINIMUM (0) - 0x26, 0x04, 0x00, // Logical Maximum 4 - 0x75, 0x08, // REPORT_SIZE (8) - 0x95, 0x01, // REPORT_COUNT (1) - 0x91, 0x02, // OUTPUT (Data,Var,Abs) - - 0x09, 0x02, // USAGE (Vendor) class address - 0x75, 0x10, // REPORT_SIZE (16) - 0x95, 0x01, // REPORT_COUNT (1) - 0x91, 0x02, // OUTPUT (Data,Var,Abs) - - 0x09, 0x03, // USAGE (Vendor) class instance - 0x75, 0x08, // REPORT_SIZE (8) - 0x95, 0x01, // REPORT_COUNT (1) - 0x91, 0x02, // OUTPUT (Data,Var,Abs) - - 0x09, 0x04, // USAGE (Vendor) cmd - 0x75, 0x20, // REPORT_SIZE (32) - 0x95, 0x01, // REPORT_COUNT (1) - 0x91, 0x02, // OUTPUT (Data,Var,Abs) - - 0x09, 0x05, // USAGE (Vendor) - 0x75, 0x40, // REPORT_SIZE (64) value - 0x95, 0x01, // REPORT_COUNT (1) - 0x91, 0x02, // OUTPUT (Data,Var,Abs) - - 0x09, 0x06, // USAGE (Vendor) address - 0x75, 0x40, // REPORT_SIZE (64) - 0x95, 0x01, // REPORT_COUNT (1) - 0x91, 0x02, // OUTPUT (Data,Var,Abs) - - 0x85,HID_ID_HIDCMD, // Report ID - 0x09, 0x01, // USAGE (Vendor) - 0x15, 0x00, // LOGICAL_MINIMUM (0) - 0x26, 0x04, 0x00, // Logical Maximum 4 - 0x75, 0x08, // REPORT_SIZE (8) - 0x95, 0x01, // REPORT_COUNT (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - - 0x09, 0x02, // USAGE (Vendor) class address - 0x75, 0x10, // REPORT_SIZE (16) - 0x95, 0x01, // REPORT_COUNT (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - - 0x09, 0x03, // USAGE (Vendor) class instance - 0x75, 0x08, // REPORT_SIZE (8) - 0x95, 0x01, // REPORT_COUNT (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - - 0x09, 0x04, // USAGE (Vendor) cmd - 0x75, 0x20, // REPORT_SIZE (32) - 0x95, 0x01, // REPORT_COUNT (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - - 0x09, 0x05, // USAGE (Vendor) - 0x75, 0x40, // REPORT_SIZE (64) value - 0x95, 0x01, // REPORT_COUNT (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) - - 0x09, 0x06, // USAGE (Vendor) address - 0x75, 0x40, // REPORT_SIZE (64) - 0x95, 0x01, // REPORT_COUNT (1) - 0x81, 0x02, // INPUT (Data,Var,Abs) + 0xC0 /* END_COLLECTION */ +}; +#endif +#ifdef FFB_HID_DESC_GAMEPAD_32B - 0xc0, // END_COLLECTION +/** + * USB HID descriptor containing a gamepad definition and the vendor defined reports but no PID FFB + */ +__ALIGN_BEGIN const uint8_t hid_gamepad_desc_32b[USB_HID_GAMEPAD_REPORT_DESC_32B_SIZE] __ALIGN_END = +{ + 0x05, 0x01, /* USAGE_PAGE (Generic Desktop)*/ + 0x09, 0x04, /* USAGE (Joystick)*/ + 0xa1, 0x01, /* COLLECTION (Application)*/ + HIDDESC_GAMEPAD_32B, + HIDDESC_CTRL_REPORTS, // HID command report support 0xC0 /* END_COLLECTION */ }; diff --git a/Firmware/Makefile b/Firmware/Makefile index 4c50b75b1..b5e4fb33c 100644 --- a/Firmware/Makefile +++ b/Firmware/Makefile @@ -26,7 +26,7 @@ BUILD_DIR = build ###################################### # Choose your board mcu F407VG or F411RE -MCU_TARGET=F407VG +MCU_TARGET ?= F407VG # The directory of mcu target TARGET_DIR = Targets/$(MCU_TARGET) @@ -36,7 +36,7 @@ TARGET_DIR = Targets/$(MCU_TARGET) TARGET = OpenFFBoard_$(MCU_TARGET) # Output directory for hex/bin files -OUTPUT_DIR = $(BUILD_DIR) +OUTPUT_DIR ?= $(BUILD_DIR) # C sources C_SOURCES = $(wildcard $(TARGET_DIR)/Core/Src/*.c) @@ -229,15 +229,15 @@ $(BUILD_DIR)/$(TARGET).elf: $(OBJECTS) Makefile $(OUTPUT_DIR)/%.hex: $(BUILD_DIR)/%.elf | $(OUTPUT_DIR) $(HEX) $< $@ - + $(OUTPUT_DIR)/%.bin: $(BUILD_DIR)/%.elf | $(OUTPUT_DIR) - $(BIN) $< $@ - + $(BIN) $< $@ + $(BUILD_DIR): - -mkdir $@ - + -mkdir -p $@ + $(OUTPUT_DIR): $(BUILD_DIR) - -mkdir $@ + -mkdir -p $@ ####################################### # clean up @@ -256,4 +256,4 @@ upload: $(BUILD_DIR)/$(TARGET).bin ####################################### -include $(wildcard $(BUILD_DIR)/*.d) -# *** EOF *** \ No newline at end of file +# *** EOF *** diff --git a/Firmware/Targets/F407VG/.cproject b/Firmware/Targets/F407VG/.cproject index f645a46aa..792292535 100644 --- a/Firmware/Targets/F407VG/.cproject +++ b/Firmware/Targets/F407VG/.cproject @@ -25,11 +25,11 @@ @@ -96,6 +108,7 @@ +