6#include <units/angle.h>
7#include <units/angular_velocity.h>
8#include <units/length.h>
13class LinearVelocityController;
32 virtual void setVelocity(units::radians_per_second_t velocity) = 0;
97 virtual units::radians_per_second_t
getError()
const {
115 using ConversionUnit =
116 units::compound_unit<units::meters, units::inverse<units::radians>>;
117 using ConversionUnit_t = units::unit_t<ConversionUnit>;
130std::unique_ptr<LinearVelocityController>
131asLinear(std::unique_ptr<AngularVelocityController> angularController,
132 AngularVelocityController::ConversionUnit_t conversion);
Definition AngularVelocityController.h:19
virtual units::radians_per_second_t getTargetVelocity() const =0
virtual void setVelocity(units::radians_per_second_t velocity)=0
virtual void setPower(double power)=0
virtual units::radian_t getPosition() const =0
virtual units::radians_per_second_t getTolerance() const =0
virtual bool atTarget() const
Definition AngularVelocityController.h:107
virtual double getPower() const =0
virtual units::radians_per_second_t getError() const
Definition AngularVelocityController.h:97
virtual units::radians_per_second_t getVelocity() const =0
virtual void setEncoderPosition(units::radian_t position=0_rad)=0
the master namespace of librmb
Definition LogitechGamepad.h:9
std::unique_ptr< LinearPositionController > asLinear(std::unique_ptr< AngularPositionController > angularController, AngularPositionController::ConversionUnit_t conversion)