librmb 1.0
Rambunction 4330 Utility Library
Loading...
Searching...
No Matches
rmb::DifferentialDrive Class Reference

#include <rmb/drive/DifferentialDrive.h>

Inheritance diagram for rmb::DifferentialDrive:
rmb::BaseDrive

Public Member Functions

 DifferentialDrive (const DifferentialDrive &)=delete
 
 DifferentialDrive (DifferentialDrive &&)=delete
 
 DifferentialDrive (std::unique_ptr< LinearVelocityController > left, std::unique_ptr< LinearVelocityController > right, std::shared_ptr< const frc::Gyro > gyro, frc::DifferentialDriveKinematics kinematics, frc::RamseteController ramseteController, std::string visionTable, const frc::Pose2d &initalPose=frc::Pose2d())
 
 DifferentialDrive (std::unique_ptr< LinearVelocityController > left, std::unique_ptr< LinearVelocityController > right, std::shared_ptr< const frc::Gyro > gyro, frc::DifferentialDriveKinematics kinematics, frc::RamseteController ramseteController, const frc::Pose2d &initalPose=frc::Pose2d())
 
void arcadeDrive (double xSpeed, double zRotation)
 
void curvatureDrive (double xSpeed, double zRotation, bool turnInPlace)
 
void tankDrive (double leftSpeed, double rightSpeed)
 
void driveWheelSpeeds (units::meters_per_second_t leftVelocity, units::meters_per_second_t rightVelocity)
 
void driveWheelSpeeds (frc::DifferentialDriveWheelSpeeds wheelSpeeds)
 
frc::DifferentialDriveWheelSpeeds getWheelSpeeds () const
 
void driveChassisSpeeds (frc::ChassisSpeeds chassisSpeeds) override
 
frc::ChassisSpeeds getChassisSpeeds () const override
 
frc::Pose2d getPose () const override
 
frc::Pose2d updatePose () override
 
void resetPose (const frc::Pose2d &pose=frc::Pose2d()) override
 
void addVisionMeasurments (const frc::Pose2d &poseEstimate, units::second_t time) override
 
void setVisionSTDevs (wpi::array< double, 3 > standardDevs) override
 
bool isHolonomic () const override
 
frc2::CommandPtr followWPILibTrajectory (frc::Trajectory trajectory, std::initializer_list< frc2::Subsystem * > driveRequirements) override
 
frc2::CommandPtr followPPPath (std::shared_ptr< pathplanner::PathPlannerPath > path, std::initializer_list< frc2::Subsystem * > driveRequirements) override
 
- Public Member Functions inherited from rmb::BaseDrive
virtual frc2::CommandPtr followWPILibTrajectoryGroup (std::vector< frc::Trajectory > trajectoryGroup, std::initializer_list< frc2::Subsystem * > driveRequirements)
 
virtual frc2::CommandPtr followPPPathWithEvents (pathplanner::PathPlannerPath path, std::unordered_map< std::string, std::shared_ptr< frc2::Command > > eventMap, std::initializer_list< frc2::Subsystem * > driveRequirements)
 
virtual frc2::CommandPtr fullPPAuto (pathplanner::PathPlannerPath path, std::unordered_map< std::string, std::shared_ptr< frc2::Command > > eventMap, std::initializer_list< frc2::Subsystem * > driveRequirements)
 
virtual frc2::CommandPtr fullPPAuto (std::vector< pathplanner::PathPlannerTrajectory > trajectoryGroup, std::unordered_map< std::string, std::shared_ptr< frc2::Command > > eventMap, std::initializer_list< frc2::Subsystem * > driveRequirements)
 

Additional Inherited Members

- Protected Member Functions inherited from rmb::BaseDrive
 BaseDrive (std::string visionTable)
 
- Protected Attributes inherited from rmb::BaseDrive
nt::DoubleArraySubscriber poseSubscriber
 
nt::DoubleArraySubscriber stdDevSubscriber
 
NT_Listener poseListener
 
NT_Listener stdDevListener
 

Detailed Description

Class to manage most aspects of a differential drivetrain from basic teleop drive funtions to odometry and full path following for both WPILib and PathPlanner trajectories.

Constructor & Destructor Documentation

◆ DifferentialDrive() [1/2]

rmb::DifferentialDrive::DifferentialDrive ( std::unique_ptr< LinearVelocityController > left,
std::unique_ptr< LinearVelocityController > right,
std::shared_ptr< const frc::Gyro > gyro,
frc::DifferentialDriveKinematics kinematics,
frc::RamseteController ramseteController,
std::string visionTable,
const frc::Pose2d & initalPose = frc::Pose2d() )

Constructs a DifferentialDrive object that automatically incorrperates vision measurments over the network for odometry.

Parameters
leftControls and monitors left side wheel speeds.
rightControls and monitors right side wheel speeds.
gyroMonitors the robots heading for odometry.
kinematicsKinematic modle for converting from wheel states to chassis states.
ramseteControllerFeedbakc controller for keeping the robot on path.
visionTablePath to the NetworkTables table for listening for vision updates.
initialPoseStarting position of the robot for odometry.

◆ DifferentialDrive() [2/2]

rmb::DifferentialDrive::DifferentialDrive ( std::unique_ptr< LinearVelocityController > left,
std::unique_ptr< LinearVelocityController > right,
std::shared_ptr< const frc::Gyro > gyro,
frc::DifferentialDriveKinematics kinematics,
frc::RamseteController ramseteController,
const frc::Pose2d & initalPose = frc::Pose2d() )

Constructs a DifferentialDrive object that does not sutomatically incorrperates vision measurments over the network for odometry.

Parameters
leftControls and monitors left side wheel speeds.
rightControls and monitors right side wheel speeds.
gyroMonitors the robots heading for odometry.
kinematicsKinematic modle for converting from wheel states to chassis states.
ramseteControllerFeedbakc controller for keeping the robot on path.
initialPoseStarting position of the robot for odometry.

Member Function Documentation

◆ addVisionMeasurments()

void rmb::DifferentialDrive::addVisionMeasurments ( const frc::Pose2d & poseEstimate,
units::second_t time )
overridevirtual

Updates the current position of the robot using latency compensated vision data.

Parameters
poseEstimateThe estimated position of the robot from vision.
timeThe time at which the data that produces this estimate was captures. This is an absolute time with with the zero eposh being the same as wpi::Now() and nt::Now(). This is usually extracted from network tables.

Implements rmb::BaseDrive.

◆ arcadeDrive()

void rmb::DifferentialDrive::arcadeDrive ( double xSpeed,
double zRotation )

Drives the robot according to the arcade algorithm which the xSpeed is added ot both sides while rotation is addef ot the left and subtracted from the right. This tends to be the most natural method for a human driver, but is quite useless for autonomouse driving since the speed of the motors is not controlled, just the power output.

Parameters
xSpeedDesired forward "speed" of the robot form -1.0 to +1.0.
zRotationDesired turnign rate of the robot from -1.0 to +1.0.

◆ curvatureDrive()

void rmb::DifferentialDrive::curvatureDrive ( double xSpeed,
double zRotation,
bool turnInPlace )

Drives the robot according to the curvature algorithm in which the turning radius of the robot is independedn from the forward speed. This is most useful for teleoperated driving as the speed of the motors is not controlled, just the power output of each motor. This is more natural for human input, but far less accurate for autonomus driving.

Parameters
xSpeedDesired forward "speed" of the robot form -1.0 to +1.0.
zRotationDesired turnign rat eof teh robot from -1.0 to +1.0.
turnInPlaceWhen true, the robot defaults back to an arcade drive so teh robot can turn in place.

◆ driveChassisSpeeds()

void rmb::DifferentialDrive::driveChassisSpeeds ( frc::ChassisSpeeds chassisSpeeds)
overridevirtual

Drives the robot via the speeds of the Chassis.

Parameters
chassisSpeedsDesired speeds of the robot Chassis.

Implements rmb::BaseDrive.

◆ driveWheelSpeeds() [1/2]

void rmb::DifferentialDrive::driveWheelSpeeds ( frc::DifferentialDriveWheelSpeeds wheelSpeeds)

Drives the wheels of the robot at the requested speeds.

Parameters
wheelSpeedsRequested speeds of the robots wheels

◆ driveWheelSpeeds() [2/2]

void rmb::DifferentialDrive::driveWheelSpeeds ( units::meters_per_second_t leftVelocity,
units::meters_per_second_t rightVelocity )

Drives the wheels of the robot at the requested speeds

Parameters
leftVelocityRequested speed of the left side wheels.
rightVelocityRequested speed of the right side wheels.

◆ followPPPath()

frc2::CommandPtr rmb::DifferentialDrive::followPPPath ( std::shared_ptr< pathplanner::PathPlannerPath > path,
std::initializer_list< frc2::Subsystem * > driveRequirements )
overridevirtual

Generates a command to follow PathPlanner Trajectory.

Parameters
trajectoryThe trajectory to follow.
driveRequirmentsThe subsystems required for driving the robot (ie. the one that contains this class)
Returns
The command to follow a trajectory.

Implements rmb::BaseDrive.

◆ followWPILibTrajectory()

frc2::CommandPtr rmb::DifferentialDrive::followWPILibTrajectory ( frc::Trajectory trajectory,
std::initializer_list< frc2::Subsystem * > driveRequirements )
overridevirtual

Generates a command to follow WPILib Trajectory.

Parameters
trajectoryThe trajectory to follow.
driveRequirmentsThe subsystems required for driving the robot (ie. the one that contains this class)
Returns
The command to follow a trajectory.

Implements rmb::BaseDrive.

◆ getChassisSpeeds()

frc::ChassisSpeeds rmb::DifferentialDrive::getChassisSpeeds ( ) const
overridevirtual

Returns the speeds of the robot chassis.

Implements rmb::BaseDrive.

◆ getPose()

frc::Pose2d rmb::DifferentialDrive::getPose ( ) const
overridevirtual

Returns the current poition without modifying it.

Implements rmb::BaseDrive.

◆ getWheelSpeeds()

frc::DifferentialDriveWheelSpeeds rmb::DifferentialDrive::getWheelSpeeds ( ) const

Returns the current speeds of the robot's wheels.

◆ isHolonomic()

bool rmb::DifferentialDrive::isHolonomic ( ) const
inlineoverridevirtual

Returns wherther the drive train is holonomic, meanign can move in all directions. This is nessesry for determining how to rezero a robot at the beginning of a path.

Implements rmb::BaseDrive.

◆ resetPose()

void rmb::DifferentialDrive::resetPose ( const frc::Pose2d & pose = frc::Pose2d())
overridevirtual

Resets the estimated robot poition.

Returns
The position to reset the robots estimated position to.

Implements rmb::BaseDrive.

◆ setVisionSTDevs()

void rmb::DifferentialDrive::setVisionSTDevs ( wpi::array< double, 3 > standardDevs)
overridevirtual

Change accuratly vision data is expected to be.

Parameters
standardDevsThe standar deviation of vision measurments. This is by how much teh actual robot positioon varies from the actual posiotion of the robot. A larger value means less acurate data. These are in units of meters and radians ordered X, Y, Theta.

Implements rmb::BaseDrive.

◆ tankDrive()

void rmb::DifferentialDrive::tankDrive ( double leftSpeed,
double rightSpeed )

Drives the robot according to the tank algorithm where the power of the motor on each side of the robot is directly controlled.This is most useful for teleoperated driving as the speed of the motors is not controlled, just the power output of each motor. This is more natural for human input, but far less accurate for autonomus driving.

Parameters
leftSpeedDesired power or the left motor from -1.0 to +1.0.
rightSpeedDesired power or the right motor from -1.0 to +1.0.

◆ updatePose()

frc::Pose2d rmb::DifferentialDrive::updatePose ( )
overridevirtual

Updates the current position of the robot using encoder and gyroscope data.

Note: Vision estimations are updated on a separate thread generated at object construction.

Returns
The updated position.

Implements rmb::BaseDrive.


The documentation for this class was generated from the following file: