Well, that way of setting the voltages is technically a valid solution. By not giving the RamseteCommand PIDControllers arguments for the left/right outputs, all the RamseteCommand will give you are the ideal speeds that the left and right sides of your robot should be running at to follow the path. This assumes you will be feeding the speeds as setpoints into a smart motor controller, that will then use PID to calculate what outputs your motors should be running while following a trajectory.
If you generated a kvVoltSecondsPerMeter from frc-characterization that is good, then I think the math would work out where dividing the speed outputs from the RamseteController by kvVoltSecondsPerMeter would just give you an ideal voltage input the motors should be at each timestep in order to follow the path correctly.
The problem with this solution is that this is all assuming an ideal world. If your robot deviated slightly due to the environment, imperfections on your robot, etc., then you would not be using any feedback to take that error into account. So you aren’t doing any PID correction to account for any potential error that could occur when following a trajectory.
To reiterate, the proper way of implementing the RamseteController given your setup, would be to use the constructor that includes the PID controllers. The PID values should be the values generated from the frc-characterization tool for the onboard controller. This will result in the output of the Ramsete controller to change to voltage outputs that have been corrected by PID Controllers that take into account external errors. By not passing the PID controllers, you just get the ideal velocity values you should run through the trajectories at without any corrections to error. This may be passable for short/simple paths, but as you get longer, more complex paths, you would start to drift and end up with less accurate trajectory following.
To be extra clear, I would implement this like the example provided in WPILib:
// Ramsete Comand from wpiLib docs example
RamseteCommand ramseteCommand = new RamseteCommand(
exampleTrajectory,
m_robotDrive::getPose,
new RamseteController(AutoConstants.kRamseteB, AutoConstants.kRamseteZeta),
new SimpleMotorFeedforward(DriveConstants.ksVolts,
DriveConstants.kvVoltSecondsPerMeter,
DriveConstants.kaVoltSecondsSquaredPerMeter),
DriveConstants.kDriveKinematics,
m_robotDrive::getWheelSpeeds,
new PIDController(DriveConstants.kPDriveVel, 0, 0),
new PIDController(DriveConstants.kPDriveVel, 0, 0),
m_robotDrive::move,
m_robotDrive
);
.
.
.
public void move(double leftVoltage, double rightVoltage) {
rightSide.setVoltage(-rightVoltage);
leftSide.setVoltage(leftVoltage);
drive.feed();
}
if you wanted to simplify the creation of the Ramsete commands to reduce the number of arguments you need to enter every time you make one, you can write a wrapper function that fills out most of the arguments that are repeated, like what my team does:
public static RamseteCommand generateRamseteCommand(DriveTrain driveTrain, ArrayList<Pose2d> path, TrajectoryConfig config) {
Trajectory trajectory = TrajectoryGenerator.generateTrajectory(path, config);
return generateRamseteCommand(driveTrain, trajectory);
}
public static RamseteCommand generateRamseteCommand(DriveTrain driveTrain, Trajectory trajectory) {
RamseteCommand ramseteCommand = new RamseteCommand (
trajectory,
driveTrain::getRobotPose,
new RamseteController(),
driveTrain.getFeedforward(),
driveTrain.getDriveTrainKinematics(),
driveTrain::getSpeeds,
driveTrain.getLeftPIDController(),
driveTrain.getRightPIDController(),
driveTrain::setVoltageOutput,
driveTrain
);
return ramseteCommand;
}