斜坡控制器

Ramsete控制器是WPILib内置的轨迹跟踪器。该跟踪器可用于通过对较小干扰的校正来准确跟踪轨迹。

构造Ramsete控制器对象

Ramsete控制器应该初始化为两个增益,即’ ‘ b ‘ ‘和’ ‘ zeta ‘ ‘。较大的值’ ‘ b ‘ ‘使收敛更猛烈,就像一个比例项,而较大的值’ ‘ zeta ‘ ‘在响应中提供更多的阻尼。这些控制器增益只决定控制器将如何输出调整的速度。它不影响机器人的实际速度跟踪。这意味着这些控制器增益通常与机器人无关。

备注

当所有单位均以米为单位时,对b和zeta的增益分别为2.0和0.7进行了反复测试,以产生理想的结果。这样,``RamseteController’’的零参数构造函数就存在,其增益默认为这些值。

// Using the default constructor of RamseteController. Here
// the gains are initialized to 2.0 and 0.7.
RamseteController controller1 = new RamseteController();

// Using the secondary constructor of RamseteController where
// the user can choose any other gains.
RamseteController controller2 = new RamseteController(2.1, 0.8);
// Using the default constructor of RamseteController. Here
// the gains are initialized to 2.0 and 0.7.
frc::RamseteController controller1;

// Using the secondary constructor of RamseteController where
// the user can choose any other gains.
frc::RamseteController controller2{2.1, 0.8};
from wpimath.controller import RamseteController

# Using the default constructor of RamseteController. Here
# the gains are initialized to 2.0 and 0.7.
controller1 = RamseteController()

# Using the secondary constructor of RamseteController where
# the user can choose any other gains.
controller2 = RamseteController(2.1, 0.8)

调整速度

Ramsete控制器返回“已调整的速度”,以便当机器人跟踪这些速度时,它可以精确地达到目标点。应使用新目标定期更新控制器。目标包括期望的姿势,期望的线速度和期望的角速度。此外,机器人的当前位置也应定期更新。控制器使用这四个参数返回调整后的线速度和角速度。用户应命令机器人以这些线性和角速度实现最佳轨迹跟踪。

备注

The “goal pose” represents the position that the robot should be at a particular timestep when tracking the trajectory. It does NOT represent the final endpoint of the trajectory.

The controller can be updated using the Calculate (C++) / calculate (Java/Python) method. There are two overloads for this method. Both of these overloads accept the current robot position as the first parameter. For the other parameters, one of these overloads takes in the goal as three separate parameters (pose, linear velocity, and angular velocity) whereas the other overload accepts a Trajectory.State object, which contains information about the goal pose. For its ease, users should use the latter method when tracking trajectories.

Trajectory.State goal = trajectory.sample(3.4); // sample the trajectory at 3.4 seconds from the beginning
ChassisSpeeds adjustedSpeeds = controller.calculate(currentRobotPose, goal);
const Trajectory::State goal = trajectory.Sample(3.4_s); // sample the trajectory at 3.4 seconds from the beginning
ChassisSpeeds adjustedSpeeds = controller.Calculate(currentRobotPose, goal);
goal = trajectory.sample(3.4)  # sample the trajectory at 3.4 seconds from the beginning
adjustedSpeeds = controller.calculate(currentRobotPose, goal)

这些计算应在每次循环迭代时执行,并具有更新的机器人位置和目标

使用调整后的速度

调整后的速度为``ChassisSpeeds’’类型,其中包含``vx’’(向前方向的线速度),``vy’’(横向方向的线速度)和``omega’’ `(围绕机器人框架中心的角速度)。由于Ramsete控制器是用于非完整机器人(不能侧向移动的机器人)的控制器,因此调整后的速度对象的``vy’’为零。

可以使用适用于您的传动系统类型的运动学类将返回的调整速度转换为可用速度。例如,可以使用``DifferentialDriveKinematics’’对象将差速器的调整速度转换为左右速度。

ChassisSpeeds adjustedSpeeds = controller.calculate(currentRobotPose, goal);
DifferentialDriveWheelSpeeds wheelSpeeds = kinematics.toWheelSpeeds(adjustedSpeeds);
double left = wheelSpeeds.leftMetersPerSecond;
double right = wheelSpeeds.rightMetersPerSecond;
ChassisSpeeds adjustedSpeeds = controller.Calculate(currentRobotPose, goal);
DifferentialDriveWheelSpeeds wheelSpeeds = kinematics.ToWheelSpeeds(adjustedSpeeds);
auto [left, right] = kinematics.ToWheelSpeeds(adjustedSpeeds);
adjustedSpeeds = controller.calculate(currentRobotPose, goal)
wheelSpeeds = kinematics.toWheelSpeeds(adjustedSpeeds)
left = wheelSpeeds.left
right = wheelSpeeds.right

Because these new left and right velocities are still speeds and not voltages, two PID Controllers, one for each side may be used to track these velocities. Either the WPILib PIDController (C++, Java, Python) can be used, or the Velocity PID feature on smart motor controllers such as the TalonSRX and the SPARK MAX can be used.

基于命令的框架中的Ramsete

For the sake of ease for users, a RamseteCommand class is built in to WPILib. For a full tutorial on implementing a path-following autonomous using RamseteCommand, see Trajectory Tutorial.