Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
robotican_hardware::CloseLoopMotor Class Reference

#include <RiCMotor.h>

Inheritance diagram for robotican_hardware::CloseLoopMotor:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void buildDevice ()=0
 CloseLoopMotor (byte id, TransportLayer *transportLayer, byte motorAddress, byte eSwitchPin, byte eSwitchType, CloseMotorType::CloseMotorType motorType, CloseMotorMode::CloseMotorMode mode)
JointInfo_tgetJointInfo ()
virtual void setParams (uint16_t speedLpfHz, uint16_t inputLpfHz, uint16_t pidHz, float speedLpfAlpha, float inputLpfAlpha, float KP, float KI, float KD, float KFF, float limit)=0
virtual void update (const DeviceMessage *deviceMessage)
virtual void write ()

Protected Member Functions

CloseMotorType::CloseMotorType getCloseMotorType ()
CloseMotorMode::CloseMotorMode getMode ()

Protected Attributes

JointInfo_t _jointInfo

Private Member Functions

bool checkIfLastCmdChange ()

Private Attributes

float _lastCmd
CloseMotorMode::CloseMotorMode _mode
CloseMotorType::CloseMotorType _motorType

Detailed Description

Definition at line 121 of file RiCMotor.h.


Constructor & Destructor Documentation

robotican_hardware::CloseLoopMotor::CloseLoopMotor ( byte  id,
TransportLayer transportLayer,
byte  motorAddress,
byte  eSwitchPin,
byte  eSwitchType,
CloseMotorType::CloseMotorType  motorType,
CloseMotorMode::CloseMotorMode  mode 
)

Definition at line 31 of file RiCMotor.cpp.


Member Function Documentation

virtual void robotican_hardware::CloseLoopMotor::buildDevice ( ) [pure virtual]

Definition at line 70 of file RiCMotor.cpp.

CloseMotorType::CloseMotorType robotican_hardware::CloseLoopMotor::getCloseMotorType ( ) [protected]

Definition at line 75 of file RiCMotor.cpp.

Definition at line 40 of file RiCMotor.cpp.

CloseMotorMode::CloseMotorMode robotican_hardware::CloseLoopMotor::getMode ( ) [protected]

Definition at line 79 of file RiCMotor.cpp.

virtual void robotican_hardware::CloseLoopMotor::setParams ( uint16_t  speedLpfHz,
uint16_t  inputLpfHz,
uint16_t  pidHz,
float  speedLpfAlpha,
float  inputLpfAlpha,
float  KP,
float  KI,
float  KD,
float  KFF,
float  limit 
) [pure virtual]
void robotican_hardware::CloseLoopMotor::update ( const DeviceMessage *  deviceMessage) [virtual]

Implements robotican_hardware::RiCMotor.

Reimplemented in robotican_hardware::CloseLoopMotorWithPotentiometer.

Definition at line 44 of file RiCMotor.cpp.


Member Data Documentation

Definition at line 142 of file RiCMotor.h.

Definition at line 123 of file RiCMotor.h.

CloseMotorMode::CloseMotorMode robotican_hardware::CloseLoopMotor::_mode [private]

Definition at line 125 of file RiCMotor.h.

CloseMotorType::CloseMotorType robotican_hardware::CloseLoopMotor::_motorType [private]

Definition at line 124 of file RiCMotor.h.


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


robotican_hardware_interface
Author(s):
autogenerated on Fri Oct 27 2017 03:02:48