Public Member Functions | Private Member Functions | Private Attributes
robotican_hardware::CloseLoopMotorWithPotentiometer Class Reference

#include <RiCMotor.h>

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

List of all members.

Public Member Functions

virtual void buildDevice ()
 CloseLoopMotorWithPotentiometer (byte id, TransportLayer *transportLayer, byte motorAddress, byte eSwitchPin, byte eSwitchType, CloseMotorType::CloseMotorType motorType, CloseMotorMode::CloseMotorMode mode, CloseMotorWithPotentiometerParam motorParam, std::string jointName)
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)
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 K, float a, float b, float tolerance, uint16_t toleranceTime, float limit)
virtual void update (const DeviceMessage *deviceMessage)
virtual void write ()

Private Member Functions

void dynamicCallback (robotican_hardware_interface::RiCBoardPotentiometerConfig &config, uint32_t level)

Private Attributes

dynamic_reconfigure::Server
< robotican_hardware_interface::RiCBoardPotentiometerConfig >
::CallbackType 
_callbackType
bool _firstTime
bool _isParamChange
boost::recursive_mutex _mutex
ros::NodeHandle _nodeHandle
CloseMotorWithPotentiometerParam _param
dynamic_reconfigure::Server
< robotican_hardware_interface::RiCBoardPotentiometerConfig > 
_server

Detailed Description

Definition at line 175 of file RiCMotor.h.


Constructor & Destructor Documentation

robotican_hardware::CloseLoopMotorWithPotentiometer::CloseLoopMotorWithPotentiometer ( byte  id,
TransportLayer transportLayer,
byte  motorAddress,
byte  eSwitchPin,
byte  eSwitchType,
CloseMotorType::CloseMotorType  motorType,
CloseMotorMode::CloseMotorMode  mode,
CloseMotorWithPotentiometerParam  motorParam,
std::string  jointName 
)

Definition at line 351 of file RiCMotor.cpp.


Member Function Documentation

Implements robotican_hardware::CloseLoopMotor.

Definition at line 307 of file RiCMotor.cpp.

void robotican_hardware::CloseLoopMotorWithPotentiometer::dynamicCallback ( robotican_hardware_interface::RiCBoardPotentiometerConfig &  config,
uint32_t  level 
) [private]

Definition at line 409 of file RiCMotor.cpp.

void robotican_hardware::CloseLoopMotorWithPotentiometer::setParams ( uint16_t  speedLpfHz,
uint16_t  inputLpfHz,
uint16_t  pidHz,
float  speedLpfAlpha,
float  inputLpfAlpha,
float  KP,
float  KI,
float  KD,
float  KFF,
float  limit 
) [virtual]

Implements robotican_hardware::CloseLoopMotor.

Definition at line 302 of file RiCMotor.cpp.

void robotican_hardware::CloseLoopMotorWithPotentiometer::setParams ( uint16_t  speedLpfHz,
uint16_t  inputLpfHz,
uint16_t  pidHz,
float  speedLpfAlpha,
float  inputLpfAlpha,
float  KP,
float  KI,
float  KD,
float  KFF,
float  K,
float  a,
float  b,
float  tolerance,
uint16_t  toleranceTime,
float  limit 
) [virtual]

Definition at line 387 of file RiCMotor.cpp.

void robotican_hardware::CloseLoopMotorWithPotentiometer::update ( const DeviceMessage *  deviceMessage) [virtual]

Reimplemented from robotican_hardware::CloseLoopMotor.

Definition at line 455 of file RiCMotor.cpp.

Reimplemented from robotican_hardware::CloseLoopMotor.

Definition at line 418 of file RiCMotor.cpp.


Member Data Documentation

dynamic_reconfigure::Server<robotican_hardware_interface::RiCBoardPotentiometerConfig>::CallbackType robotican_hardware::CloseLoopMotorWithPotentiometer::_callbackType [private]

Definition at line 184 of file RiCMotor.h.

Definition at line 180 of file RiCMotor.h.

Definition at line 177 of file RiCMotor.h.

Definition at line 181 of file RiCMotor.h.

Reimplemented from robotican_hardware::Device.

Definition at line 179 of file RiCMotor.h.

Definition at line 178 of file RiCMotor.h.

dynamic_reconfigure::Server<robotican_hardware_interface::RiCBoardPotentiometerConfig> robotican_hardware::CloseLoopMotorWithPotentiometer::_server [private]

Definition at line 183 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