|
LightLib
PROS library for VEX V5: EKF/MCL localization, RAMSETE path following, high-level chassis API
|
#include <odomChassisController.hpp>
Public Member Functions | |
| OdomChassisController (TimeUtil itimeUtil, std::shared_ptr< Odometry > iodometry, const StateMode &imode=StateMode::FRAME_TRANSFORMATION, const QLength &imoveThreshold=0_mm, const QAngle &iturnThreshold=0_deg, std::shared_ptr< Logger > ilogger=Logger::getDefaultLogger()) | |
| Odometry based chassis controller. | |
| ~OdomChassisController () override | |
| OdomChassisController (const OdomChassisController &)=delete | |
| OdomChassisController (OdomChassisController &&other)=delete | |
| OdomChassisController & | operator= (const OdomChassisController &other)=delete |
| OdomChassisController & | operator= (OdomChassisController &&other)=delete |
| virtual void | driveToPoint (const Point &ipoint, bool ibackwards=false, const QLength &ioffset=0_mm)=0 |
| Drives the robot straight to a point in the odom frame. | |
| virtual void | turnToPoint (const Point &ipoint)=0 |
| Turns the robot to face a point in the odom frame. | |
| virtual void | turnToAngle (const QAngle &iangle)=0 |
| Turns the robot to face an angle in the odom frame. | |
| virtual OdomState | getState () const |
| virtual void | setState (const OdomState &istate) |
| Set a new state to be the current state. | |
| void | setDefaultStateMode (const StateMode &imode) |
| Sets a default StateMode that will be used to interpret target points and query the Odometry state. | |
| virtual void | setMoveThreshold (const QLength &imoveThreshold) |
| Set a new move threshold. | |
| virtual void | setTurnThreshold (const QAngle &iturnTreshold) |
| Set a new turn threshold. | |
| virtual QLength | getMoveThreshold () const |
| virtual QAngle | getTurnThreshold () const |
| void | startOdomThread () |
| Starts the internal odometry thread. | |
| CrossplatformThread * | getOdomThread () const |
| std::shared_ptr< Odometry > | getOdometry () |
Public Member Functions inherited from okapi::ChassisController | |
| ChassisController ()=default | |
| A ChassisController adds a closed-loop layer on top of a ChassisModel. | |
| virtual | ~ChassisController ()=default |
| virtual void | moveDistance (QLength itarget)=0 |
| Drives the robot straight for a distance (using closed-loop control). | |
| virtual void | moveRaw (double itarget)=0 |
| Drives the robot straight for a distance (using closed-loop control). | |
| virtual void | moveDistanceAsync (QLength itarget)=0 |
| Sets the target distance for the robot to drive straight (using closed-loop control). | |
| virtual void | moveRawAsync (double itarget)=0 |
| Sets the target distance for the robot to drive straight (using closed-loop control). | |
| virtual void | turnAngle (QAngle idegTarget)=0 |
| Turns the robot clockwise in place (using closed-loop control). | |
| virtual void | turnRaw (double idegTarget)=0 |
| Turns the robot clockwise in place (using closed-loop control). | |
| virtual void | turnAngleAsync (QAngle idegTarget)=0 |
| Sets the target angle for the robot to turn clockwise in place (using closed-loop control). | |
| virtual void | turnRawAsync (double idegTarget)=0 |
| Sets the target angle for the robot to turn clockwise in place (using closed-loop control). | |
| virtual void | setTurnsMirrored (bool ishouldMirror)=0 |
| Sets whether turns should be mirrored. | |
| virtual bool | isSettled ()=0 |
| Checks whether the internal controllers are currently settled. | |
| virtual void | waitUntilSettled ()=0 |
| Delays until the currently executing movement completes. | |
| virtual void | stop ()=0 |
| Interrupts the current movement to stop the robot. | |
| virtual void | setMaxVelocity (double imaxVelocity)=0 |
| Sets a new maximum velocity in RPM [0-600]. | |
| virtual double | getMaxVelocity () const =0 |
| virtual ChassisScales | getChassisScales () const =0 |
| Get the ChassisScales. | |
| virtual AbstractMotor::GearsetRatioPair | getGearsetRatioPair () const =0 |
| Get the GearsetRatioPair. | |
| virtual std::shared_ptr< ChassisModel > | getModel ()=0 |
| virtual ChassisModel & | model ()=0 |
Protected Member Functions | |
| void | loop () |
Static Protected Member Functions | |
| static void | trampoline (void *context) |
Protected Attributes | |
| std::shared_ptr< Logger > | logger |
| TimeUtil | timeUtil |
| QLength | moveThreshold |
| QAngle | turnThreshold |
| std::shared_ptr< Odometry > | odom |
| CrossplatformThread * | odomTask {nullptr} |
| std::atomic_bool | dtorCalled {false} |
| StateMode | defaultStateMode {StateMode::FRAME_TRANSFORMATION} |
| std::atomic_bool | odomTaskRunning {false} |
Definition at line 22 of file odomChassisController.hpp.
| okapi::OdomChassisController::OdomChassisController | ( | TimeUtil | itimeUtil, |
| std::shared_ptr< Odometry > | iodometry, | ||
| const StateMode & | imode = StateMode::FRAME_TRANSFORMATION, |
||
| const QLength & | imoveThreshold = 0_mm, |
||
| const QAngle & | iturnThreshold = 0_deg, |
||
| std::shared_ptr< Logger > | ilogger = Logger::getDefaultLogger() |
||
| ) |
Odometry based chassis controller.
Starts task at the default for odometry when constructed, which calls Odometry::step every 10ms. The default StateMode is StateMode::FRAME_TRANSFORMATION.
Moves the robot around in the odom frame. Instead of telling the robot to drive forward or turn some amount, you instead tell it to drive to a specific point on the field or turn to a specific angle relative to its starting position.
| itimeUtil | The TimeUtil. |
| iodometry | The Odometry instance to run in a new task. |
| imode | The new default StateMode used to interpret target points and query the Odometry state. |
| imoveThreshold | minimum length movement (smaller movements will be skipped) |
| iturnThreshold | minimum angle turn (smaller turns will be skipped) |
|
override |
|
delete |
|
delete |
|
pure virtual |
Drives the robot straight to a point in the odom frame.
| ipoint | The target point to navigate to. |
| ibackwards | Whether to drive to the target point backwards. |
| ioffset | An offset from the target point in the direction pointing towards the robot. The robot will stop this far away from the target point. |
Implemented in okapi::DefaultOdomChassisController.
|
virtual |
| std::shared_ptr< Odometry > okapi::OdomChassisController::getOdometry | ( | ) |
| CrossplatformThread * okapi::OdomChassisController::getOdomThread | ( | ) | const |
|
virtual |
|
virtual |
|
protected |
|
delete |
|
delete |
| void okapi::OdomChassisController::setDefaultStateMode | ( | const StateMode & | imode | ) |
Sets a default StateMode that will be used to interpret target points and query the Odometry state.
| imode | The new default StateMode. |
|
virtual |
Set a new move threshold.
Any requested movements smaller than this threshold will be skipped.
| imoveThreshold | new move threshold |
|
virtual |
Set a new state to be the current state.
The default StateMode is StateMode::FRAME_TRANSFORMATION.
| istate | The new state in the given format. |
| imode | The mode to treat the input state as. |
|
virtual |
Set a new turn threshold.
Any requested turns smaller than this threshold will be skipped.
| iturnTreshold | new turn threshold |
| void okapi::OdomChassisController::startOdomThread | ( | ) |
Starts the internal odometry thread.
This should not be called by normal users.
|
staticprotected |
|
pure virtual |
Turns the robot to face an angle in the odom frame.
| iangle | The angle to turn to. |
Implemented in okapi::DefaultOdomChassisController.
|
pure virtual |
Turns the robot to face a point in the odom frame.
| ipoint | The target point to turn to face. |
Implemented in okapi::DefaultOdomChassisController.
|
protected |
Definition at line 148 of file odomChassisController.hpp.
|
protected |
Definition at line 147 of file odomChassisController.hpp.
|
protected |
Definition at line 141 of file odomChassisController.hpp.
|
protected |
Definition at line 143 of file odomChassisController.hpp.
|
protected |
Definition at line 145 of file odomChassisController.hpp.
|
protected |
Definition at line 146 of file odomChassisController.hpp.
|
protected |
Definition at line 149 of file odomChassisController.hpp.
|
protected |
Definition at line 142 of file odomChassisController.hpp.
|
protected |
Definition at line 144 of file odomChassisController.hpp.