|
Quad-SDK
|
Forward command controller for quad. More...
#include <controller_plugin.h>


Public Member Functions | |
| QuadController () | |
| Forward command controller for a set of effort controlled joints (torque or force). | |
| bool | init (hardware_interface::EffortJointInterface *hw, ros::NodeHandle &n) |
| void | update (const ros::Time &, const ros::Duration &) |
Public Attributes | |
| std::vector< std::string > | joint_names_ |
| std::vector< hardware_interface::JointHandle > | joints_ |
| realtime_tools::RealtimeBuffer< BufferType > | commands_buffer_ |
| unsigned int | n_joints_ |
Private Types | |
| typedef std::vector< quad_msgs::LegCommand > | BufferType |
Private Member Functions | |
| void | commandCB (const quad_msgs::LegCommandArrayConstPtr &msg) |
| void | enforceJointLimits (double &command, unsigned int index) |
Forward command controller for quad.
This class forwards the commanded efforts down to a set of joints.
| effort_controllers::QuadController::QuadController | ( | ) |
Forward command controller for a set of effort controlled joints (torque or force).
This class forwards the commanded efforts down to a set of joints.
| type | Must be "JointGroupEffortController". |
| joints | List of names of the joints to control. |
Subscribes to: