mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-21 01:01:43 +00:00
Cleaned up C++ examples (#672)
This commit is contained in:
committed by
Peter Johnson
parent
6401aa1fde
commit
45d48d6b5a
@@ -6,9 +6,10 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <AnalogGyro.h>
|
||||
#include <Drive/MecanumDrive.h>
|
||||
#include <IterativeRobot.h>
|
||||
#include <Joystick.h>
|
||||
#include <RobotDrive.h>
|
||||
#include <Spark.h>
|
||||
|
||||
/**
|
||||
* This is a sample program that uses mecanum drive with a gyro sensor to
|
||||
@@ -20,18 +21,19 @@ public:
|
||||
void RobotInit() override {
|
||||
// invert the left side motors
|
||||
// you may need to change or remove this to match your robot
|
||||
myRobot.SetInvertedMotor(RobotDrive::kFrontLeftMotor, true);
|
||||
myRobot.SetInvertedMotor(RobotDrive::kRearLeftMotor, true);
|
||||
m_frontLeft.SetInverted(true);
|
||||
m_rearLeft.SetInverted(true);
|
||||
|
||||
gyro.SetSensitivity(kVoltsPerDegreePerSecond);
|
||||
m_gyro.SetSensitivity(kVoltsPerDegreePerSecond);
|
||||
}
|
||||
|
||||
/**
|
||||
* Mecanum drive is used with the gyro angle as an input.
|
||||
*/
|
||||
void TeleopPeriodic() override {
|
||||
myRobot.MecanumDrive_Cartesian(joystick.GetX(), joystick.GetY(),
|
||||
joystick.GetZ(), gyro.GetAngle());
|
||||
m_robotDrive.DriveCartesian(m_joystick.GetX(),
|
||||
m_joystick.GetY(), m_joystick.GetZ(),
|
||||
m_gyro.GetAngle());
|
||||
}
|
||||
|
||||
private:
|
||||
@@ -40,16 +42,21 @@ private:
|
||||
static constexpr double kVoltsPerDegreePerSecond = 0.0128;
|
||||
|
||||
static constexpr int kFrontLeftMotorPort = 0;
|
||||
static constexpr int kFrontRightMotorPort = 1;
|
||||
static constexpr int kRearLeftMotorPort = 2;
|
||||
static constexpr int kRearLeftMotorPort = 1;
|
||||
static constexpr int kFrontRightMotorPort = 2;
|
||||
static constexpr int kRearRightMotorPort = 3;
|
||||
static constexpr int kGyroPort = 0;
|
||||
static constexpr int kJoystickPort = 0;
|
||||
|
||||
frc::RobotDrive myRobot{kFrontLeftMotorPort, kFrontRightMotorPort,
|
||||
kRearLeftMotorPort, kRearRightMotorPort};
|
||||
frc::AnalogGyro gyro{kGyroPort};
|
||||
frc::Joystick joystick{kJoystickPort};
|
||||
frc::Spark m_frontLeft{kFrontLeftMotorPort};
|
||||
frc::Spark m_rearLeft{kRearLeftMotorPort};
|
||||
frc::Spark m_frontRight{kFrontRightMotorPort};
|
||||
frc::Spark m_rearRight{kRearRightMotorPort};
|
||||
frc::MecanumDrive m_robotDrive{
|
||||
m_frontLeft, m_rearLeft, m_frontRight, m_rearRight};
|
||||
|
||||
frc::AnalogGyro m_gyro{kGyroPort};
|
||||
frc::Joystick m_joystick{kJoystickPort};
|
||||
};
|
||||
|
||||
START_ROBOT_CLASS(Robot)
|
||||
|
||||
Reference in New Issue
Block a user