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

#include <RiCMotor.h>

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

List of all members.

Public Member Functions

virtual void buildDevice ()
 CloseLoopMotorWithEncoder (byte id, TransportLayer *transportLayer, byte motorAddress, byte eSwitchPin, byte eSwitchType, CloseMotorType::CloseMotorType motoryType, CloseMotorMode::CloseMotorMode mode, CloseMotorWithEncoderParam param, std::string jointName)
virtual void write ()

Private Member Functions

void dynamicCallback (robotican_hardware_interface::RiCBoardConfig &config, uint32_t level)
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)
void timerCallback (const ros::TimerEvent &e)

Private Attributes

dynamic_reconfigure::Server
< robotican_hardware_interface::RiCBoardConfig >
::CallbackType 
_callbackType
bool _isSetParam
boost::recursive_mutex _mutex
ros::NodeHandle _nodeHandle
CloseMotorWithEncoderParam _params
dynamic_reconfigure::Server
< robotican_hardware_interface::RiCBoardConfig > 
_server
ros::AsyncSpinner _spinner
ros::Publisher _statusPub
ros::Timer _timer

Detailed Description

Definition at line 148 of file RiCMotor.h.


Constructor & Destructor Documentation

robotican_hardware::CloseLoopMotorWithEncoder::CloseLoopMotorWithEncoder ( byte  id,
TransportLayer transportLayer,
byte  motorAddress,
byte  eSwitchPin,
byte  eSwitchType,
CloseMotorType::CloseMotorType  motoryType,
CloseMotorMode::CloseMotorMode  mode,
CloseMotorWithEncoderParam  param,
std::string  jointName 
)

Definition at line 168 of file RiCMotor.cpp.


Member Function Documentation

Implements robotican_hardware::CloseLoopMotor.

Definition at line 202 of file RiCMotor.cpp.

void robotican_hardware::CloseLoopMotorWithEncoder::dynamicCallback ( robotican_hardware_interface::RiCBoardConfig &  config,
uint32_t  level 
) [private]

Definition at line 288 of file RiCMotor.cpp.

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

Implements robotican_hardware::CloseLoopMotor.

Definition at line 243 of file RiCMotor.cpp.

Definition at line 295 of file RiCMotor.cpp.

Reimplemented from robotican_hardware::CloseLoopMotor.

Definition at line 259 of file RiCMotor.cpp.


Member Data Documentation

dynamic_reconfigure::Server<robotican_hardware_interface::RiCBoardConfig>::CallbackType robotican_hardware::CloseLoopMotorWithEncoder::_callbackType [private]

Definition at line 159 of file RiCMotor.h.

Definition at line 156 of file RiCMotor.h.

Definition at line 152 of file RiCMotor.h.

Reimplemented from robotican_hardware::Device.

Definition at line 151 of file RiCMotor.h.

Definition at line 150 of file RiCMotor.h.

dynamic_reconfigure::Server<robotican_hardware_interface::RiCBoardConfig> robotican_hardware::CloseLoopMotorWithEncoder::_server [private]

Definition at line 158 of file RiCMotor.h.

Definition at line 153 of file RiCMotor.h.

Definition at line 154 of file RiCMotor.h.

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