#include <joint_torque_controller.h>
Public Member Functions | |
std::vector< std::vector< int > > | getRawMotorCommands (double position, double velocity) |
bool | initialize (std::string name, std::string port_namespace, dynamixel_hardware_interface::DynamixelIO *dxl_io) |
void | processCommand (const std_msgs::Float64ConstPtr &msg) |
void | processMotorStates (const dynamixel_hardware_interface::MotorStateListConstPtr &msg) |
bool | processSetVelocity (dynamixel_hardware_interface::SetVelocity::Request &req, dynamixel_hardware_interface::SetVelocity::Request &res) |
bool | processTorqueEnable (dynamixel_hardware_interface::TorqueEnable::Request &req, dynamixel_hardware_interface::TorqueEnable::Request &res) |
bool | setVelocity (double velocity) |
Private Member Functions | |
int16_t | velRad2Enc (double vel_rad) |
Definition at line 47 of file joint_torque_controller.h.
std::vector<std::vector<int> > controller::JointTorqueController::getRawMotorCommands | ( | double | position, |
double | velocity | ||
) | [virtual] |
Implements controller::SingleJointController.
bool controller::JointTorqueController::initialize | ( | std::string | name, |
std::string | port_namespace, | ||
dynamixel_hardware_interface::DynamixelIO * | dxl_io | ||
) | [virtual] |
Reimplemented from controller::SingleJointController.
void controller::JointTorqueController::processCommand | ( | const std_msgs::Float64ConstPtr & | msg | ) | [virtual] |
Implements controller::SingleJointController.
void controller::JointTorqueController::processMotorStates | ( | const dynamixel_hardware_interface::MotorStateListConstPtr & | msg | ) | [virtual] |
Implements controller::SingleJointController.
bool controller::JointTorqueController::processSetVelocity | ( | dynamixel_hardware_interface::SetVelocity::Request & | req, |
dynamixel_hardware_interface::SetVelocity::Request & | res | ||
) | [virtual] |
Implements controller::SingleJointController.
bool controller::JointTorqueController::processTorqueEnable | ( | dynamixel_hardware_interface::TorqueEnable::Request & | req, |
dynamixel_hardware_interface::TorqueEnable::Request & | res | ||
) | [virtual] |
Reimplemented from controller::SingleJointController.
bool controller::JointTorqueController::setVelocity | ( | double | velocity | ) | [virtual] |
Implements controller::SingleJointController.
int16_t controller::JointTorqueController::velRad2Enc | ( | double | vel_rad | ) | [private] |