#include <Servo.h>
Public Member Functions | |
virtual void | buildDevice () |
virtual void | deviceAck (const DeviceAck *ack) |
JointInfo_t * | getJointInfo () |
Servo (byte id, TransportLayer *transportLayer, byte pin, float a, float b, float max, float min, float initPos, std::string jointName) | |
void | setParam (float a, float b, float max, float min) |
virtual void | update (const DeviceMessage *deviceMessage) |
virtual void | write () |
Private Member Functions | |
bool | checkIfLastCmdChange () |
void | dynamicCallback (robotican_hardware_interface::RiCBoardServoConfig &config, uint32_t level) |
Private Attributes | |
float | _a |
float | _b |
dynamic_reconfigure::Server < robotican_hardware_interface::RiCBoardServoConfig > ::CallbackType | _callbackType |
bool | _isChangeParam |
JointInfo_t | _jointInfo |
float | _lastCmd |
float | _max |
float | _min |
boost::recursive_mutex | _mutex |
ros::NodeHandle | _nodeHandle |
byte | _pin |
dynamic_reconfigure::Server < robotican_hardware_interface::RiCBoardServoConfig > | _server |
robotican_hardware::Servo::Servo | ( | byte | id, |
TransportLayer * | transportLayer, | ||
byte | pin, | ||
float | a, | ||
float | b, | ||
float | max, | ||
float | min, | ||
float | initPos, | ||
std::string | jointName | ||
) |
void robotican_hardware::Servo::buildDevice | ( | ) | [virtual] |
Implements robotican_hardware::Device.
bool robotican_hardware::Servo::checkIfLastCmdChange | ( | ) | [private] |
void robotican_hardware::Servo::deviceAck | ( | const DeviceAck * | ack | ) | [virtual] |
Reimplemented from robotican_hardware::Device.
void robotican_hardware::Servo::dynamicCallback | ( | robotican_hardware_interface::RiCBoardServoConfig & | config, |
uint32_t | level | ||
) | [private] |
void robotican_hardware::Servo::setParam | ( | float | a, |
float | b, | ||
float | max, | ||
float | min | ||
) |
void robotican_hardware::Servo::update | ( | const DeviceMessage * | deviceMessage | ) | [virtual] |
Implements robotican_hardware::Device.
void robotican_hardware::Servo::write | ( | ) | [virtual] |
Implements robotican_hardware::Device.
float robotican_hardware::Servo::_a [private] |
float robotican_hardware::Servo::_b [private] |
dynamic_reconfigure::Server<robotican_hardware_interface::RiCBoardServoConfig>::CallbackType robotican_hardware::Servo::_callbackType [private] |
bool robotican_hardware::Servo::_isChangeParam [private] |
float robotican_hardware::Servo::_lastCmd [private] |
float robotican_hardware::Servo::_max [private] |
float robotican_hardware::Servo::_min [private] |
boost::recursive_mutex robotican_hardware::Servo::_mutex [private] |
Reimplemented from robotican_hardware::Device.
byte robotican_hardware::Servo::_pin [private] |
dynamic_reconfigure::Server<robotican_hardware_interface::RiCBoardServoConfig> robotican_hardware::Servo::_server [private] |