Motors
package com.arcrobotics.ftclib.hardware.motors
FTCLib offers fully-featured motor wrappers for the ease of the user. Behind the scenes, it utilizes the advanced features of FTCLib to produce a more powerful implementation of the DcMotor objects offered in the SDK. Similarly, FTCLib has a Motor
and MotorEx
object, each of which allow for the user to directly access the instance object from the hardware map in the case of wanting to work with it directly.
Creating a Motor Object
Creating a motor is as simple as passing in the hardware map, the name of the device in the robot controller config, and an optional third parameter of a GoBILDA motor type. This is necessary because the goBILDA motors in the configuration don't specify the different max RPM (rotations per minute) and CPR (counts per revolution).
There is also an option of using a custom CPR and RPM value.
Using a RunMode
A RunMode is a method of running the motor when power is supplied. There are three modes: VelocityControl
, PositionControl
, and RawPower
.
Raw power sets the motor power directly through a value of where the value represents the percentage of its maximum speed. This is also open loop control, which means there is no feedback control. This is the default mode of the motor.
Position control has the motor run to a desired position based on the input speed and the distance between current motor position and target position (in counts). This utilizes a P controller whose coefficient can be changed using setPositionCoefficient(double)
. This is a tuned value. For tuning, we currently recommend using FTC Dashboard.
Velocity control has the motor run using velocity in ticks per second with both a feedback and feedforward controller rather than simply setting the speed to a percentage of the maximum output speed. This can lead to smoother control for your motors, and is highly recommended for autonomous programs.
Setting Behaviors
FTCLib, like the SDK, has wrapper methods for setting the ZeroPowerBehavior and the direction of the motors. ZeroPowerBehavior is often used for mechanisms other than the drivetrain; for example, like how you would use the BRAKE behavior for a lift.
The Built-In Encoder
A lot of motors have built-in encoders. FTCLib offers a nested class Motor.Encoder
that utilizes advanced mechanics and corrects for velocity overflow. One of the other great things is that resetting the encoder does not require stopping the motor. It calculates an offset and subtracts that from the current position. This offset is set to the current position of the encoder each time the reset()
method is called. The Motor object also has methods that manipulate the encoder so that you don't have to grab the internal encoder instance from the object.
You can also use the built-in encoder as an encoder itself when using an external encoder.
The MotorEx Object
MotorEx is an implementation of the Motor class with better integrated velocity control. Unlike the Motor object, it uses the corrected velocity by default instead of the raw velocity. It also uses the DcMotorEx
object instead of the DcMotor
. Calling getVelocity()
will return the corrected velocity value.
You can also set the velocity directly using setVelocity()
. You can pass the angular rate and the angle unit (optional). Passing just the angular rate will set the velocity in ticks per second. Passing an angle unit will set the velocity to units per second, depending on the unit that is passed into the method.
Bulk Reading
A bulk read reads all of the sensor data (except i2c) on a lynx module to save cycle times. Bulk reads were introduced in SDK version 5.4. Since FTCLib uses wrappers, we can treat them the same way as other sensors.
Here's a sample implementation of auto-caching.
You can also take a look at this sample in the SDK.
CRServo
Th CRServo class is just a motor object intended to be used for a continuous rotation servo. To use it, you create a custom implementation of the Motor
interface where you pass a CRServo
object from the SDK into the constructor. Then, using the CRServo
class in FTCLib, you can extend its functionality and capabilities.
MotorGroup
A motor group takes a group of motors and acts like a single motor. It utilizes an array of motors and takes in a varargs to produce simple actions like moving in a group.
Last updated