librmb 1.0
Rambunction 4330 Utility Library
Loading...
Searching...
No Matches
rmb::BaseDrive Class Referenceabstract

#include <rmb/drive/BaseDrive.h>

Inheritance diagram for rmb::BaseDrive:
rmb::DifferentialDrive rmb::SwerveDrive< NumModules >

Public Member Functions

virtual void driveChassisSpeeds (frc::ChassisSpeeds chassisSpeeds)=0
 
virtual frc::ChassisSpeeds getChassisSpeeds () const =0
 
virtual frc::Pose2d getPose () const =0
 
virtual frc::Pose2d updatePose ()=0
 
virtual void addVisionMeasurments (const frc::Pose2d &poseEstimate, units::second_t time)=0
 
virtual void setVisionSTDevs (wpi::array< double, 3 > standardDevs)=0
 
virtual void resetPose (const frc::Pose2d &pose=frc::Pose2d())=0
 
virtual bool isHolonomic () const =0
 
virtual frc2::CommandPtr followWPILibTrajectory (frc::Trajectory trajectory, std::initializer_list< frc2::Subsystem * > driveRequirements)=0
 
virtual frc2::CommandPtr followWPILibTrajectoryGroup (std::vector< frc::Trajectory > trajectoryGroup, std::initializer_list< frc2::Subsystem * > driveRequirements)
 
virtual frc2::CommandPtr followPPPath (std::shared_ptr< pathplanner::PathPlannerPath > path, std::initializer_list< frc2::Subsystem * > driveRequirements)=0
 
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)
 

Protected Member Functions

 BaseDrive (std::string visionTable)
 

Protected Attributes

nt::DoubleArraySubscriber poseSubscriber
 
nt::DoubleArraySubscriber stdDevSubscriber
 
NT_Listener poseListener
 
NT_Listener stdDevListener
 

Detailed Description

Base interface for robot drive classes that can handle automatic updating of vision based odometry and more complex path following.

Constructor & Destructor Documentation

◆ BaseDrive()

rmb::BaseDrive::BaseDrive ( std::string visionTable)
protected

Constructs a base drive class capable of automatically listening for vision based odometry over the network via NetworkTables.

Parameters
visionTablePath to NetworkTables table for listening for vision based odometry updates. This table whould include two DoubleArrayTopics. One titled pose with three entries ordered X, Y, Theta in meters and radians. The other should be names stDev with three entris again ordered X, Y, Theta with units meters and radians. Always update stDev before pose.

Member Function Documentation

◆ addVisionMeasurments()

virtual void rmb::BaseDrive::addVisionMeasurments ( const frc::Pose2d & poseEstimate,
units::second_t time )
pure virtual

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.

Implemented in rmb::DifferentialDrive, and rmb::SwerveDrive< NumModules >.

◆ driveChassisSpeeds()

virtual void rmb::BaseDrive::driveChassisSpeeds ( frc::ChassisSpeeds chassisSpeeds)
pure virtual

Drives the robot via the speeds of the Chassis.

Parameters
chassisSpeedsDesired speeds of the robot Chassis.

Implemented in rmb::DifferentialDrive, and rmb::SwerveDrive< NumModules >.

◆ followPPPath()

virtual frc2::CommandPtr rmb::BaseDrive::followPPPath ( std::shared_ptr< pathplanner::PathPlannerPath > path,
std::initializer_list< frc2::Subsystem * > driveRequirements )
pure virtual

Generates a command to follow PathPlanner Trajectory.

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

Implemented in rmb::DifferentialDrive, and rmb::SwerveDrive< NumModules >.

◆ followPPPathWithEvents()

virtual frc2::CommandPtr rmb::BaseDrive::followPPPathWithEvents ( pathplanner::PathPlannerPath path,
std::unordered_map< std::string, std::shared_ptr< frc2::Command > > eventMap,
std::initializer_list< frc2::Subsystem * > driveRequirements )
virtual

Generates a command to follow a vector of PathPlanner Trajectories. This is helpful if the robot should stop in the middle of a path or changes direction.

Parameters
trajectorygroupThe vector of trajectories to follow.
driveRequirementsThe subsystems required for driving the robot (ie. the one that contains this class)
Returns
The command to follow a list of trajectories. Generates a command to follow a PathPlanner Trajectories with events. When each event is triggered, the robot will execute the corosponding commmand in the event map while continuing to follow the path.
Parameters
trajectoryThe trajectory to follow.
evenMapUsed to map event names to thier corosponding commands for execution during the trajectory.
driveRequirementsThe subsystems required for driving the robot (ie. the one that contains this class)
Returns
The command to follow a trajectory with events.

◆ followWPILibTrajectory()

virtual frc2::CommandPtr rmb::BaseDrive::followWPILibTrajectory ( frc::Trajectory trajectory,
std::initializer_list< frc2::Subsystem * > driveRequirements )
pure virtual

Generates a command to follow WPILib Trajectory.

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

Implemented in rmb::DifferentialDrive, and rmb::SwerveDrive< NumModules >.

◆ followWPILibTrajectoryGroup()

virtual frc2::CommandPtr rmb::BaseDrive::followWPILibTrajectoryGroup ( std::vector< frc::Trajectory > trajectoryGroup,
std::initializer_list< frc2::Subsystem * > driveRequirements )
virtual

Generates a command to follow a vector of WPILib Trajectories. This is helpful if the robot should stop in the middle of a path or changes direction.

Parameters
trajectorygroupThe vector of trajectories to follow.
driveRequirementsThe subsystems required for driving the robot (ie. the one that contains this class)
Returns
The command to follow a list of trajectories.

◆ fullPPAuto() [1/2]

virtual frc2::CommandPtr rmb::BaseDrive::fullPPAuto ( pathplanner::PathPlannerPath path,
std::unordered_map< std::string, std::shared_ptr< frc2::Command > > eventMap,
std::initializer_list< frc2::Subsystem * > driveRequirements )
virtual

Generates a command to follow a vector of PathPlanner Trajectories with events. When each event is triggered, the robot will execute the corosponding commmand in the event map while continuing to follow the path.

Parameters
trajectoryGroupThe vector of trajectories to follow.
evenMapUsed to map event names to thier corosponding commands for execution during the trajectories.
driveRequirementsThe subsystems required for driving the robot (ie. the one that contains this class)
Returns
The command to follow a list of trajectories with events. Generates a command to complete a full autonomouse routine generated by PathPlanner. Beyond just a path with events, this includes resetting the position at the start of the path and executing stop events.
Parameters
trajectoryThe trajectory to follow.
evenMapUsed to map event names to thier corosponding commands for execution during the trajectories.
driveRequirementsThe subsystems required for driving the robot (ie. the one that contains this class)
Returns
The command to follow a full autonomus routine.

◆ fullPPAuto() [2/2]

virtual frc2::CommandPtr rmb::BaseDrive::fullPPAuto ( std::vector< pathplanner::PathPlannerTrajectory > trajectoryGroup,
std::unordered_map< std::string, std::shared_ptr< frc2::Command > > eventMap,
std::initializer_list< frc2::Subsystem * > driveRequirements )
virtual

Generates a command to complete a full autonomouse routine generated by PathPlanner. Beyond just a path with events, this includes resetting the position at the start of the path and executing stop events.

Parameters
trajectoryGroupThe vector of trajectories to follow.
evenMapUsed to map event names to thier corosponding commands for execution during the trajectories.
driveRequirementsThe subsystems required for driving the robot (ie. the one that contains this class)
Returns
The command to follow a full autonomus routine.

◆ getChassisSpeeds()

virtual frc::ChassisSpeeds rmb::BaseDrive::getChassisSpeeds ( ) const
pure virtual

Returns the speeds of the robot chassis.

Implemented in rmb::DifferentialDrive, and rmb::SwerveDrive< NumModules >.

◆ getPose()

virtual frc::Pose2d rmb::BaseDrive::getPose ( ) const
pure virtual

Returns the current poition estimation without modifying it.

Implemented in rmb::DifferentialDrive, and rmb::SwerveDrive< NumModules >.

◆ isHolonomic()

virtual bool rmb::BaseDrive::isHolonomic ( ) const
pure virtual

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.

Implemented in rmb::DifferentialDrive, and rmb::SwerveDrive< NumModules >.

◆ resetPose()

virtual void rmb::BaseDrive::resetPose ( const frc::Pose2d & pose = frc::Pose2d())
pure virtual

Resets the estimated robot poition.

Returns
The position to reset the robots estimated to.

Implemented in rmb::DifferentialDrive, and rmb::SwerveDrive< NumModules >.

◆ setVisionSTDevs()

virtual void rmb::BaseDrive::setVisionSTDevs ( wpi::array< double, 3 > standardDevs)
pure virtual

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.

Implemented in rmb::DifferentialDrive, and rmb::SwerveDrive< NumModules >.

◆ updatePose()

virtual frc::Pose2d rmb::BaseDrive::updatePose ( )
pure virtual

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

Returns
The updated position.

Implemented in rmb::DifferentialDrive, and rmb::SwerveDrive< NumModules >.

Member Data Documentation

◆ poseListener

NT_Listener rmb::BaseDrive::poseListener
protected

Handle for keeping track of vision position callback for position.

◆ poseSubscriber

nt::DoubleArraySubscriber rmb::BaseDrive::poseSubscriber
protected

Network Tables subscriber for vision position predictions.

Data is sent in a three entry double array ordered X, Y, Theta. X and Y are in meters and Theta is in radians.

◆ stdDevListener

NT_Listener rmb::BaseDrive::stdDevListener
protected

Handle for keeping track of vision position standard deviations callback for position.

◆ stdDevSubscriber

nt::DoubleArraySubscriber rmb::BaseDrive::stdDevSubscriber
protected

Network Tables subscriber for the standard deviation of vision predictions.

Data is sent in a three entry double array ordered X, Y, Theta. X and Y are in meters and Theta is in radians. The standard deviations are a measure of how much the reported position typically deviates from the true position. Larger values denote less accuracy in vision data, while smaller values denote higher accuracy.


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