Resurgence (PY2022)
Codebase for the Husky Robotics 2021-2022 rover Resurgence
|
Cnet::ardupilot::ArduPilotProtocol | |
Cautonomous::AutonomousTask | |
▼Crobot::base_motor | An abstract motor class |
Crobot::can_motor | |
Crobot::sim_motor | |
Ccam::Camera | Represents a camera on the rover, from which a video feed can be retrieved |
Ccam::CameraConfig | A struct that represents the information outlined in Camera Configuration |
Ccam::CameraParams | Represents a set of intrinsic camera parameters |
Ccommands::command_t | |
▼Ccommands::CommandBase | |
Ccommands::DriveToWaypointCommand | Provides robot drive velocity commands to navigate the robot to a given waypoint given the velocity parameters to drive the robot at, the proportional factor to steer the robot with and the 2D Cartesian position of the target in the world reference frame |
CDataPoint< T > | Represents data measured using a sensor at a given time |
Crobot::types::DataPoint< T > | Represents data measured using a sensor at a given time |
CAR::Detector | |
CDiffDriveKinematics | Represents the kinematics of a differential drive |
Ckinematics::DiffDriveKinematics | Represents the kinematics of a differential drive |
Ckinematics::DiffWristKinematics | Represents the kinematics of a differential wrist |
Ccontrol::drive_commands_t | The power commands to all four drive motors |
Ch264encoder::Encoder | |
Ch264encoder::EncoderImpl | |
Crobot::encparams_t | |
Cnavtypes::eulerangles_t | |
▼Cstd::exception [external] | |
Ccam::invalid_camera_config | Exception for errors in the camera configuration |
▼Cstd::runtime_error [external] | |
Crobot::types::bad_datapoint_access | |
▼Ckinematics::ForwardArmKinematics< D, N > | A class that calculates the forward kinematics of an arm |
Ckinematics::ArmKinematics< 2, N > | |
Ckinematics::ArmKinematics< D, N > | A class that combines the forward and inverse kinematics of an arm |
▼Ckinematics::ForwardArmKinematics< 2, N > | |
Ckinematics::PlanarArmFK< N > | Kinematics object for a sequence of arm segments in a 2d plane |
Ckinematics::gearpos_t | Represents the positions (or power) of the two motor-driven gears in the differential wrist |
Cnavtypes::gpscoords_t | Represents a GPS coordinate in degrees |
CGPSDatum | A GPS datum that specifies the reference ellipsoid for use in GPS calculations |
CGPSToMetersConverter | A class used to convert gps coordinates to coordinates on a flat xy-plane, and vice versa |
Cvideo::H264Encoder | This class encodes OpenCV frames into encoded H264 data that can be sent to an H264 decoder, like JMuxer |
Cstd::hash< std::pair< T1, T2 > > | |
▼Ckinematics::InverseArmKinematics< D, N > | A class that calculates the inverse kinematics of an arm |
Ckinematics::ArmKinematics< 2, N > | |
Ckinematics::ArmKinematics< D, N > | A class that combines the forward and inverse kinematics of an arm |
▼Ckinematics::InverseArmKinematics< 2, N > | |
Ckinematics::FabrikSolver2D< N > | Implementation of the FABRIK algorithm, in the special case of 2 dimensions |
Ccontrol::JacobianPosController< outputDim, inputDim > | This class controls the position of a multidimensional mechanism with a trapezoidal velocity profile using the jacobian of the kinematics |
CJacobianVelController< outputDim, inputDim > | This class controls the velocity of a multidimensional mechanism by commanding its position using the jacobian of the kinematics |
Ckinematics::jointpos_t | Represents the position (or power) of the differential wrist joint |
▼Cfilters::KalmanFilterBase< stateDim, inputDim > | Base class for Kalman Filters |
Cfilters::ExtendedKalmanFilter< stateDim, inputDim, outputDim, processNoiseDim, outputNoiseDim > | Implements a discrete-time EKF |
Cfilters::KalmanFilter< stateDim, inputDim, outputDim > | Implements a Kalman Filter |
Cfilters::MultiSensorEKF< stateDim, inputDim, processNoiseDim, numOutputs > | |
Cutil::latch | Implementation of a countdown latch for threading synchronization |
CLimitSwitchData | A class that represents limit switches from a specific motor |
Crobot::types::LimitSwitchData | A class that represents limit switches from a specific motor |
CAR::MarkerPattern | A class to represent the pattern that may appear on a physical AR tag, NOT a physical instance of a tag itself; each individual instance of the pattern as it appears in the world is represented by an instance of the Tag class, and there may be multiple Tags corresponding to the same MarkerPattern |
CAR::MarkerSet | Represents a "set" of markers used for a competition, containing the markers that should be recognized for that competition and also some other information like the physical (real-world) size of the tags |
CMat | |
Cfilters::statespace::NoiseCovMat< stateDim, size, paramSize > | Represents a square noise covariance matrix |
▼Cutil::impl::Notifiable | |
▼Cutil::AsyncTask< std::chrono::steady_clock > | |
▼Cutil::PeriodicTask< Clock > | Implements a task that executes a function periodically |
Cnet::mc::tasks::ArmIKTask | This task sets the arm joint positions to track the current IK command |
Cnet::mc::tasks::PowerRepeatTask | This task is responsible for periodically resending setMotorPower commands to the motors |
Cnet::mc::tasks::TelemReportTask | This task periodically sends robot telemetry data to Mission Control |
Cutil::PeriodicScheduler< std::chrono::steady_clock > | |
▼Cutil::AsyncTask< Clock > | An abstract class that can be overridden to run long-running tasks and encapsulate task-related data |
Cnet::mc::tasks::CameraStreamTask | This task is responsible for sending the camera streams to Mission Control over websocket |
Cutil::PeriodicScheduler< Clock > | Uses a single thread to periodically invoke callbacks at a given frequency |
Cutil::PeriodicTask< Clock > | Implements a task that executes a function periodically |
Cutil::Watchdog< Clock > | Implements a thread-safe watchdog |
Cfilters::Output | Represent an output for a system |
Ccan::packettype_t | The types of CAN packets that we recognize |
Crobot::pidcoef_t | A struct containing a set of PID coefficients |
Ccontrol::PIDController< dim > | A PID controller for multiple independent dimensions |
Ccontrol::PIDGains | A set of PID gains |
Ccontrol::PlanarArmController< N > | Controller to move planar arm to a target end effector position |
Crobot::potparams_t | Represents parameters defining a potentiometer scale |
Cutil::RAIIHelper | A helper class for executing a function when leaving a scope, in RAII-style |
Cfilters::RollingAvgFilter< T > | Implements a rolling average filter of the specified type |
CRollingAvgFilter< T > | Implements a rolling average filter of the specified type |
Cutil::ScopedTimer | A utility class that helps with timing |
Ccan::motor::sensor_t | The supported motor position sensors |
Cnet::mc::SingleClientWSServer | A WebSocket server class that only accepts a single client at a time to each endpoint served by this server |
Cnet::websocket::SingleClientWSServer | A WebSocket server class that only accepts a single client at a time to each endpoint served by this server |
Ccontrol::SingleDimTrapezoidalVelocityProfile | Trapezoidal velocity profile in a single dimension |
Ccontrol::swerve_rots_t | Represents the rotations of all four steer motors in in millidegrees |
Ccontrol::SwerveController | Controller to handle the wheel rotations for driving with swerve modes |
Ckinematics::SwerveDriveKinematics | Calculates forward and inverse drivebase kinematics for a 4-wheel swerve drivebase with specifiable width and length |
Ckinematics::swervewheelvel_t | Represents robot wheel velocities in robot reference frame, in polar form (wheel speed and angle) |
CAR::Tag | Class representing an AR tag detected in an image |
Ccontrol::TrapezoidalVelocityProfile< dim > | Trapezoidal velocity profile in multiple dimensions |
▼Cnet::mc::WebSocketProtocol | Defines a protocol which will be served at an endpoint of a server |
Cnet::mc::MissionControlProtocol | |
▼Cnet::websocket::WebSocketProtocol | Defines a protocol which will be served at an endpoint of a server |
Cnet::mc::MissionControlProtocol | |
Ckinematics::wheelvel_t | |
Ch264encoder::x264_nal_t_simple |