acmerobotics / road-runner

Wheeled mobile robot motion planning library designed for FTC
MIT License
239 stars 85 forks source link

The curve for x linear velocity from timeTrajectory from SplineTest is not smooth? #107

Open hallw opened 5 months ago

hallw commented 5 months ago

Tuning RoadRunner following the instructions, all seem went well until the final step with the SplineTest. The robot changes heading drastically for (~half a second) in the middle of movement. At the beginning I thought it is due to incorrect heading gain, but after I remove all gains (no feedback), I still see the same.

I finally decided to draw graph with command.linearVel.x.value(), command.linearVel.y.value() and command.angVel.value(), command being the return value of below:

        PoseVelocity2dDual<Time> command = new HolonomicController(
                PARAMS.axialGain, PARAMS.lateralGain, PARAMS.headingGain,
                PARAMS.axialVelGain, PARAMS.lateralVelGain, PARAMS.headingVelGain
        )
                .compute(txWorldTarget, pose, robotVelRobot);

In my understanding, since the trajectory is roughly a half circle, for most of the time x linear velocity should be a constant, except or a short period of ramp up and ramp down, while both y linear velocity and angular velocity should be both small. But what I'm surprised to see the curve for x linear velocity has a "sharp angle" in the middle, around when 2 spline path connects. I think this is causing the robot to change heading drastically?

The trajectory is like below (same as SplineTest from QuickStart except left/right flipped):

            drive.actionBuilder(beginPose)
                    .splineTo(new Vector2d(30, 30 * direction()), Math.PI / 2 * direction())
                    .splineTo(new Vector2d(0, 60 * direction()), Math.PI)
                    .build());

Screen recording of FTC Dashboard attached.

https://github.com/acmerobotics/road-runner/assets/12581739/0f119c07-ee1a-46e0-a7cd-d9a1915a2cc0

rbrott commented 4 months ago

But what I'm surprised to see the curve for x linear velocity has a "sharp angle" in the middle, around when 2 spline path connects. I think this is causing the robot to change heading drastically?

The planned x/y linear velocity are continuous (you're looking in the robot frame but the same is true for the field/world frame), so the planned heading will also be continuous. Only continuity of velocity is guaranteed though, and the acceleration will switch abruptly which likely causes the abrupt robot motion.

hallw commented 3 months ago

Yes it is caused by acceleration switch from MAX to -MAX. So this is expected in RoadRunner trajectory planning? In a trajectory we do want the robot to speed up quickly so the MAX won't be too small. So to avoid abruption the "workaround" is to split the trajectory into segments and specify different max acceleration seperately?

rbrott commented 3 months ago

Yes it is caused by acceleration switch from MAX to -MAX. So this is expected in RoadRunner trajectory planning?

Yes, abrupt acceleration changes are expected with the default constraints. You'll end up with a profile similar to this: image You can get a smoother result if you'll willing to compromise some constraints. Replacing the default velocity constraint with a simple translational one gives image You can also fiddle with the path. The fundamental issue here is the path curvature. I'll probably replace the current path with a single spline that's better behaved.

So to avoid abruption the "workaround" is to split the trajectory into segments and specify different max acceleration seperately?

I wouldn't do this. As mentioned above, try tweaking the path first and then relaxing constraints second.