librmb 1.0
Rambunction 4330 Utility Library
|
#include <rmb/drive/DifferentialDrive.h>
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 |
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.
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.
left | Controls and monitors left side wheel speeds. |
right | Controls and monitors right side wheel speeds. |
gyro | Monitors the robots heading for odometry. |
kinematics | Kinematic modle for converting from wheel states to chassis states. |
ramseteController | Feedbakc controller for keeping the robot on path. |
visionTable | Path to the NetworkTables table for listening for vision updates. |
initialPose | Starting position of the robot for odometry. |
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.
left | Controls and monitors left side wheel speeds. |
right | Controls and monitors right side wheel speeds. |
gyro | Monitors the robots heading for odometry. |
kinematics | Kinematic modle for converting from wheel states to chassis states. |
ramseteController | Feedbakc controller for keeping the robot on path. |
initialPose | Starting position of the robot for odometry. |
|
overridevirtual |
Updates the current position of the robot using latency compensated vision data.
poseEstimate | The estimated position of the robot from vision. |
time | The 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.
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.
xSpeed | Desired forward "speed" of the robot form -1.0 to +1.0. |
zRotation | Desired turnign rate of the robot from -1.0 to +1.0. |
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.
xSpeed | Desired forward "speed" of the robot form -1.0 to +1.0. |
zRotation | Desired turnign rat eof teh robot from -1.0 to +1.0. |
turnInPlace | When true, the robot defaults back to an arcade drive so teh robot can turn in place. |
|
overridevirtual |
Drives the robot via the speeds of the Chassis.
chassisSpeeds | Desired speeds of the robot Chassis. |
Implements rmb::BaseDrive.
void rmb::DifferentialDrive::driveWheelSpeeds | ( | frc::DifferentialDriveWheelSpeeds | wheelSpeeds | ) |
Drives the wheels of the robot at the requested speeds.
wheelSpeeds | Requested speeds of the robots wheels |
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
leftVelocity | Requested speed of the left side wheels. |
rightVelocity | Requested speed of the right side wheels. |
|
overridevirtual |
Generates a command to follow PathPlanner Trajectory.
trajectory | The trajectory to follow. |
driveRequirments | The subsystems required for driving the robot (ie. the one that contains this class) |
Implements rmb::BaseDrive.
|
overridevirtual |
Generates a command to follow WPILib Trajectory.
trajectory | The trajectory to follow. |
driveRequirments | The subsystems required for driving the robot (ie. the one that contains this class) |
Implements rmb::BaseDrive.
|
overridevirtual |
Returns the speeds of the robot chassis.
Implements rmb::BaseDrive.
|
overridevirtual |
Returns the current poition without modifying it.
Implements rmb::BaseDrive.
frc::DifferentialDriveWheelSpeeds rmb::DifferentialDrive::getWheelSpeeds | ( | ) | const |
Returns the current speeds of the robot's wheels.
|
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.
|
overridevirtual |
Resets the estimated robot poition.
Implements rmb::BaseDrive.
|
overridevirtual |
Change accuratly vision data is expected to be.
standardDevs | The 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.
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.
leftSpeed | Desired power or the left motor from -1.0 to +1.0. |
rightSpeed | Desired power or the right motor from -1.0 to +1.0. |
|
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.
Implements rmb::BaseDrive.