Format speed as percentage
This commit is contained in:
parent
dcd0307186
commit
3fe756cdaf
|
@ -4,6 +4,7 @@ import com.qualcomm.robotcore.eventloop.opmode.OpMode;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||||
|
import java.text.DecimalFormat;
|
||||||
|
|
||||||
@TeleOp(name = "TELEOP - USE THIS ONE")
|
@TeleOp(name = "TELEOP - USE THIS ONE")
|
||||||
public class DriveTeleOp extends OpMode {
|
public class DriveTeleOp extends OpMode {
|
||||||
|
@ -61,7 +62,8 @@ public class DriveTeleOp extends OpMode {
|
||||||
motorLiftLeft.setPower(powerLift);
|
motorLiftLeft.setPower(powerLift);
|
||||||
motorLiftRight.setPower(powerLift);
|
motorLiftRight.setPower(powerLift);
|
||||||
|
|
||||||
telemetry.addData("speed", String.format("%.2f", speed));
|
DecimalFormat df = new DecimalFormat("#%");
|
||||||
|
telemetry.addData("speed", df.format(speed));
|
||||||
telemetry.update();
|
telemetry.update();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in a new issue