WPILibC++  unspecified
MecanumDrive.h
1 /*----------------------------------------------------------------------------*/
2 /* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
3 /* Open Source Software - may be modified and shared by FRC teams. The code */
4 /* must be accompanied by the FIRST BSD license file in the root directory of */
5 /* the project. */
6 /*----------------------------------------------------------------------------*/
7 
8 #pragma once
9 
10 #include <memory>
11 
12 #include <llvm/raw_ostream.h>
13 
14 #include "Drive/RobotDriveBase.h"
15 
16 namespace frc {
17 
18 class SpeedController;
19 
65 class MecanumDrive : public RobotDriveBase {
66  public:
67  MecanumDrive(SpeedController& frontLeftMotor, SpeedController& rearLeftMotor,
68  SpeedController& frontRightMotor,
69  SpeedController& rearRightMotor);
70  ~MecanumDrive() override = default;
71 
72  MecanumDrive(const MecanumDrive&) = delete;
73  MecanumDrive& operator=(const MecanumDrive&) = delete;
74 
75  void DriveCartesian(double x, double y, double rotation,
76  double gyroAngle = 0.0);
77  void DrivePolar(double magnitude, double angle, double rotation);
78 
79  void StopMotor() override;
80  void GetDescription(llvm::raw_ostream& desc) const override;
81 
82  void InitSendable(SendableBuilder& builder) override;
83 
84  private:
85  SpeedController& m_frontLeftMotor;
86  SpeedController& m_rearLeftMotor;
87  SpeedController& m_frontRightMotor;
88  SpeedController& m_rearRightMotor;
89 
90  bool reported = false;
91 };
92 
93 } // namespace frc
Interface for speed controlling devices.
Definition: SpeedController.h:17
Definition: RobotController.cpp:14
void DriveCartesian(double x, double y, double rotation, double gyroAngle=0.0)
Drive method for Mecanum platform.
Definition: MecanumDrive.cpp:60
void DrivePolar(double magnitude, double angle, double rotation)
Drive method for Mecanum platform.
Definition: MecanumDrive.cpp:107
A class for driving Mecanum drive platforms.
Definition: MecanumDrive.h:65
MecanumDrive(SpeedController &frontLeftMotor, SpeedController &rearLeftMotor, SpeedController &frontRightMotor, SpeedController &rearRightMotor)
Construct a MecanumDrive.
Definition: MecanumDrive.cpp:28
Definition: SendableBuilder.h:23
void InitSendable(SendableBuilder &builder) override
Initializes this Sendable object.
Definition: MecanumDrive.cpp:131
This class implements an extremely fast bulk output stream that can only output to a stream...
Definition: raw_ostream.h:33
Common base class for drive platforms.
Definition: RobotDriveBase.h:26