#include <RiCMotor.h>

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_t * | getJointInfo () |
| 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 |
Definition at line 121 of file RiCMotor.h.
| 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.
| virtual void robotican_hardware::CloseLoopMotor::buildDevice | ( | ) | [pure virtual] |
Implements robotican_hardware::RiCMotor.
Implemented in robotican_hardware::CloseLoopMotorWithPotentiometer, and robotican_hardware::CloseLoopMotorWithEncoder.
| bool robotican_hardware::CloseLoopMotor::checkIfLastCmdChange | ( | ) | [private] |
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.
| void robotican_hardware::CloseLoopMotor::write | ( | ) | [virtual] |
Implements robotican_hardware::RiCMotor.
Reimplemented in robotican_hardware::CloseLoopMotorWithPotentiometer, and robotican_hardware::CloseLoopMotorWithEncoder.
Definition at line 53 of file RiCMotor.cpp.
Definition at line 142 of file RiCMotor.h.
float robotican_hardware::CloseLoopMotor::_lastCmd [private] |
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.