broncbotz3481 / yagsl Goto Github PK
View Code? Open in Web Editor NEWYet Another General Swerve Library
License: Apache License 2.0
Yet Another General Swerve Library
License: Apache License 2.0
You often need to retry multiple times in order to get a good reading. This all happens during bootup so normally in the disabled state so waiting a little longer is no problem. Even then going without a good CANCoder measurement will cause you to drag a wheel which is just bad.
Link to democat code
Moved to YAGSL-Example; sorry, not sure how to close the issue.
Set closed loop ramp rate to avoid rapid battery drain.
I generated a config for SwerveDrive using https://broncbotz3481.github.io/YAGSL-Example/, and the robot code reports:
Unrecognized field "conversionFactor" (class swervelib.parser.json.SwerveDriveJson), not marked as ignorable (3 known properties: "imu", "invertedIMU", "modules"]) at [Source: (File); line: 8, column: 24] (through reference chain: swervelib.parser.json.SwerveDriveJson["conversionFactor"])
If I remove conversionFactor from swerveDrive.json
, the code crashes again (but differently):
Error at swervelib.parser.SwerveParser.createSwerveDrive(SwerveParser.java:139): Unhandled exception: java.lang.NullPointerException: Cannot assign field "angle" because "swervelib.parser.SwerveParser.physicalPropertiesJson.conversionFactor" is null
Since SwerveParser.java gets the angle and drive conversion factors from physicalproperties.json
,
public SwerveDrive createSwerveDrive(SimpleMotorFeedforward driveFeedforward, double maxSpeed,
double angleMotorConversionFactor, double driveMotorConversion)
{
physicalPropertiesJson.conversionFactor.angle = angleMotorConversionFactor;
physicalPropertiesJson.conversionFactor.drive = driveMotorConversion;
return createSwerveDrive(driveFeedforward, maxSpeed);
}
I tried moving "conversionFactor" to physicalProperties.json
, and the code works.
i want to use a VictorSPX for the angle motor, i've implemented a basic version of it in my fork of the yagsl-example repo here it is You really dont need an encoder for the angle motor if you have an absolute encoder so i see no reason not to implement it. And maybe you can add support for more motor drivers.
#56 is the same issue, and it was closed because the gyro apparently applies the offset while the robot isn't moving.
However, I don't see the offset being applied anywhere, and comparing the gyro yaw and the robot angle reported by SwerveDrive::field
shows they aren't the same angle.
pidfprop -- er -- ties is written in a few places as
pidfprop -- re -- ties. This is a hard to spot typo.
1. IN https://github.com/BroncBotz3481/YAGSL/wiki/Swerve-Module-PIDF-Properties
"Swerve Module PID Configuration (pidfpropreties.json)"
AND ALSO
"JSON Configurations
swervedrive.json
controllerproperties.json
pidfpropreties.json
2. IN https://github.com/BroncBotz3481/YAGSL/wiki/JSON
"Click on each JSON below to see the configuration options
swervedrive.json
controllerproperties.json
pidfpropreties.json"
Currently, these constants are calculated by public static SimpleMotorFeedforward createDriveFeedforward(double optimalVoltage, double maxSpeed, double wheelGripCoefficientOfFriction)
in SwerveMath
, however I would like a way to provide my own kV, kA, and kS, constants so I can use my sysid calculated values.
You could add an optional entry to one of the JSONs.
The ability to zero the drive encoders makes it possible to re-run an auto path in PathPlannerLib with the need to restart the robot.
We implemented an example here. Thanks!
FRC5010/FRCLibrary@6a492c1
Hi! I want to use this library with WPILIB 2024. But it is incompatible with the 2024 version of WPILIB.
* What went wrong:
An exception occurred applying plugin request [id: 'edu.wpi.first.GradleRIO', version: '2024.1.1-beta-3']
> Failed to apply plugin class 'edu.wpi.first.gradlerio.wpi.WPIPlugin'.
> Could not create an instance of type edu.wpi.first.gradlerio.wpi.WPIExtension.
> Vendor Dependency YAGSL has invalid year null. Expected to be 2024
YAGSL assumes a periodic rate of 50Hz, presumably since that's the approximate rate the default periodic() methods and command scheduler runs at. However, some teams prefer to specify faster update rates. YAGSL uses hard-coded values when specifying the loop update rate, rendering it incompatible with other rates.
As far as I can see, this is only done in line 467 of SwerveDrive.java for discretization to correct for translation skew when rotating. Still, it'd be nice if this were changed to a user-configurable variable to allow for faster loops without breaking compatibility with this correction.
My team updated our swerve code to the next-gen update, and despite not changing our PID values, our driving seems to be completely shot. It drives in weird jerky motions and wrong directions, as well as continuing to jerk around when the joystick isn't being touched. I've attached a video of it before the update, and two after (one of motion and one of attempted standstill)
Hello,
I am a FRC software mentor trying to make use of the YAGSL template to operate a swerve drive and I am having issues with getting heading correction to work correctly with the current version of the template. I am currently using a NavX2 gyro and have observed the following results:
Out of curiosity, I have swapped from using YAGSL as vendor dependency to just using it as a folder in my robot project template so I can test and debug changes. Based on testing so far this block of code stood out to me.
YAGSL/swervelib/SwerveDrive.java
Lines 449 to 466 in bd949c2
lastHeadingRadians
value is being used as the current measurement for the rather than heading of the current pose for the heading controller. Is there a reason for this? Swapping the arguments applied to this controller seems to fix heading correction for my swerve configuration.
Also I noticed a use of a correctionEnabled
flag, which appears to be used as a toggle to continuously update the lastRadianHeadings
variable. Is this variable actually needed? I was able to replace the above code block with the following and it seemed to allow heading correction to work correctly:
if (headingCorrection)
{
if (Math.abs(velocity.omegaRadiansPerSecond) < HEADING_CORRECTION_DEADBAND
&& (Math.abs(velocity.vxMetersPerSecond) > HEADING_CORRECTION_DEADBAND
|| Math.abs(velocity.vyMetersPerSecond) > HEADING_CORRECTION_DEADBAND))
{
velocity.omegaRadiansPerSecond =
swerveController.headingCalculate(getPose().getRotation().getRadians(), lastHeadingRadians);
}
else
{
lastHeadingRadians = getPose().getRotation().getRadians();
}
}
I am not sure what is policy regarding making updates and/or contributions to this repository or if this something already being worked on, so I am merely just bringing this issue up with a possible solution with hopes of an official fix or clarification on how to use this template in the future.
Hello, we are currently tuning our YAGSL PIDF values and I'm wondering if there is a recommended way to do it in a more dynamic fashion.
Currently, our programmer is changing the value in the JSON, deploying, testing and then repeat.
I have been looking for ways to speed up this feedback loop if there are any recommendations?
I tried modifying the P value from code, during runtime doing something like this:
swerveDrive.getModules()[0].configuration.velocityPIDF.p = 0.5
But this does not work. I have been trying to find a setter method or something like that in the JavaDocs, but I'm not finding anything.
Am I missing something here? Is it possible to modify these values programmatically? Thanks!
I saw that the krakens had been added, so I wanted to know if the Vortex motors will be added?
Can you update the configuration generator site with the navx_usb option under swervedrive.json
We have CTRE Mag encoders and are attaching them directly to the Falcon motor to get the absolute rotation encoding.
Would love to see support for that.
We are having an issue as we now have the offsets to be correct, but it seems like the rotation of the robot isnt working. We have tried all sorts of different values and it still seems to not work properly. It will keep overshooting its setpoint regardless of what PID values are entered. If we set a really high D value, it will overshoot worse, but I assume that is normal for a PD loop that is destructively resonating (I cant think of the right term).
I also tried turning the invert IMU both ways and no change seems to happen.
My team uses yagsl, and would like the ability to orient the drive angles without moving, to help precise alignment using April tags.
The SwerveDrive class has a 'lockPose()method that sets the module desired states, and uses
force=truein calls to
module.setDesiredState()` But from the outside of SwerveDrive, I don't see a great way to directly set the orientation without a speed above 1%, due to anti-jitter logic.
One fix would be to add an optional 'force' boolean to setModuleStates
, and pass that along to setRawModuleStates
public void setModuleStates(SwerveModuleState[] desiredStates, boolean isOpenLoop) {
setRawModuleStates(
kinematics.toSwerveModuleStates(kinematics.toChassisSpeeds(desiredStates)), isOpenLoop, false);
}
public void setModuleStates(SwerveModuleState[] desiredStates, boolean isOpenLoop, boolean force) {
setRawModuleStates(
kinematics.toSwerveModuleStates(kinematics.toChassisSpeeds(desiredStates)), isOpenLoop, force);
}
If desired, I could make a PR for this. My ability to test on a robot is limited, because the team needs the robot for actual driving.
I'm new and trying to read through and understand the YAGSL library code. If I understand this function correctly, the purpose of this function is supposed to be to calculate the maximum angular velocity of the robot possible from the maximum linear speed of the robot.
The given equation in line 129 is
return maxSpeed / new Rotation2d(furthestModuleX, furthestModuleY).getRadians();
[meter/sec] / [radians] = [meters/(sec*radians)]
which is the speed of the robot divided by the angle of furthest module in radians, something I don't believe was intended. I suspect the intended value is the maxSpeed divided by the radius of the circle centered on the theoretical center of the swerve drive system and running through the furthest module, which would be
return maxSpeed / Math.sqrt(furthestModuleX*furthestModuleX+furthestModuleY*furthestModuleY);
[meters/sec / radius(meters)] = radians/sec
Also, in line 36 of SwerveControllConfiguration this function is called just using the position of module 0 without checking to see which module is farthest from the center.
My apologies if I misunderstand the code or made a mistake somewhere...
Using the link https://broncbotz3481.github.io/YAGSL-Lib/yagsl/yagsl.json to install YAGSL in a 2024 FRC project does not work because the JSON file does not contain a value for "frcYear". I tried the link https://github.com/BroncBotz3481/YAGSL-Lib/blob/2024/yagsl/yagsl.json but it also does not work.
Currently drive speed starts at .1 * maximumSpeed where it needs to start at 0 and reach maximum speed.
No way to run the configMountPose method for a pigeon2 imu
sizeLeftRight and sizeFrontBack don't seem to be used but are wrong. The position of the modules is already half of the side length (since it is position from the center) so doesn't need to be divided by 2.
I would also convert that back to inches before I publish to shuffleboard since the user facing units seem to be in Imperial.
If all the Through Bore Encoder IDs are set to 0 which I would assume would be fine, the code crashes on start. Current work around give them different IDs
It could be related to the other issue regarding Through bore IDs but on the smart dashboard the through bore encoders just jitter around, but dont respond to any change in the wheel's rotation.
Most importantly the Falcon motors.
I am currently trying to make a swerve drive using the newist online download link on the documentation page (https://broncbotz3481.github.io/YAGSL-Lib/yagsl/yagsl.json): version "2023.1.6" . When I attempt to make my drivetrain with Swerve = new SwerveParser(new File(Filesystem.getDeployDirectory(), "swerve")).createSwerveDrive(5.0);
my intellisense returns that there isn't a method of createSwerveDrive(double)
even though there is one in the javadocs. This is probly just me misunderstanding how these dot functions work rather than a mismatch of javadoc version to downloadable version, but I think it could still be a good addition for the future.
WPILIB's toSwerveStates method allows you to specify a point with Translation2d to rotate around, it would be super useful to have this implemented to YAGSL
In DeviceJson.java when selecting navx i2c, a warning is shown when selecting navx_i2c; however, return new NavXSwerve(I2C.Port.kMXP);
is sent. The onboard i2c is different than the mxp i2c, and I2C.Port.kMXP isn't the device that has known issues.
Hi! Our robot is going too slow in simulation. When I increase max speed(10) I think it goes normally. But at max speed 1 it is already really fast in real life. What can we do for simulation?
Our code located here:
https://github.com/EmirTolluoglu/9231Panthers/tree/main
A declarative, efficient, and flexible JavaScript library for building user interfaces.
๐ Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.
TypeScript is a superset of JavaScript that compiles to clean JavaScript output.
An Open Source Machine Learning Framework for Everyone
The Web framework for perfectionists with deadlines.
A PHP framework for web artisans
Bring data to life with SVG, Canvas and HTML. ๐๐๐
JavaScript (JS) is a lightweight interpreted programming language with first-class functions.
Some thing interesting about web. New door for the world.
A server is a program made to process requests and deliver data to clients.
Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.
Some thing interesting about visualization, use data art
Some thing interesting about game, make everyone happy.
We are working to build community through open source technology. NB: members must have two-factor auth.
Open source projects and samples from Microsoft.
Google โค๏ธ Open Source for everyone.
Alibaba Open Source for everyone
Data-Driven Documents codes.
China tencent open source team.