#include <JointTorqueLimiter.h>

Public Member Functions | |
| bool | getCompletionMessage (r2_msgs::StringArray &completionMsg) |
| void | initializeMaps () |
| Initialize maps and iterate through elements, find the joints and set the data and torque to zero. | |
| JointTorqueLimiter (const std::string &urdfFile) | |
| Constructor for Joint Torque Limiter. | |
| int | populateTorqueMsg (sensor_msgs::JointState &tauLimCmd) |
| Fill out header, resize message if needed, and fill in torque message. | |
| void | setYankLimit (const double lim) |
| Set Yank limit on the joint torque limiter lim Value to set yank limit. | |
| int | storeJointTorques (const double &tau) |
| Fill out header, resize message if needed, and fill in torque message. | |
| int | storeJointTorques (const sensor_msgs::JointState &desiredTauLim) |
| Match chain properties to jntArray properties and store the torque value for each joint. | |
| ~JointTorqueLimiter () | |
Public Attributes | |
| std::map< std::string, double > | jointTorqueLimMap |
Private Attributes | |
| RateLimiter | yl |
Definition at line 14 of file JointTorqueLimiter.h.
| JointTorqueLimiter::JointTorqueLimiter | ( | const std::string & | urdfFile | ) |
Constructor for Joint Torque Limiter.
Definition at line 7 of file JointTorqueLimiter.cpp.
Definition at line 12 of file JointTorqueLimiter.cpp.
| bool JointTorqueLimiter::getCompletionMessage | ( | r2_msgs::StringArray & | completionMsg | ) |
Definition at line 137 of file JointTorqueLimiter.cpp.
| void JointTorqueLimiter::initializeMaps | ( | ) |
Initialize maps and iterate through elements, find the joints and set the data and torque to zero.
Definition at line 31 of file JointTorqueLimiter.cpp.
| int JointTorqueLimiter::populateTorqueMsg | ( | sensor_msgs::JointState & | tauLim | ) |
Fill out header, resize message if needed, and fill in torque message.
| tauLim | Torque message |
Definition at line 62 of file JointTorqueLimiter.cpp.
| void JointTorqueLimiter::setYankLimit | ( | const double | lim | ) |
Set Yank limit on the joint torque limiter lim Value to set yank limit.
Definition at line 21 of file JointTorqueLimiter.cpp.
| int JointTorqueLimiter::storeJointTorques | ( | const double & | tau | ) |
Fill out header, resize message if needed, and fill in torque message.
| tauLim | Torque message |
Definition at line 94 of file JointTorqueLimiter.cpp.
| int JointTorqueLimiter::storeJointTorques | ( | const sensor_msgs::JointState & | desiredTauLim | ) |
Match chain properties to jntArray properties and store the torque value for each joint.
| desiredTauLim | Joint state to check in the jointTorqueLimMap |
Definition at line 115 of file JointTorqueLimiter.cpp.
| std::map<std::string, double> JointTorqueLimiter::jointTorqueLimMap |
Definition at line 27 of file JointTorqueLimiter.h.
RateLimiter JointTorqueLimiter::yl [private] |
Definition at line 30 of file JointTorqueLimiter.h.