Forward command controller for a set of effort controlled joints (torque or force). More...
#include <joint_group_position_controller.h>
Public Attributes | |
realtime_tools::RealtimeBuffer< std::vector< double > > | commands_buffer_ |
std::vector< std::string > | joint_names_ |
std::vector< hardware_interface::JointHandle > | joints_ |
unsigned int | n_joints_ |
Public Attributes inherited from controller_interface::ControllerBase | |
CONSTRUCTED | |
INITIALIZED | |
RUNNING | |
enum controller_interface::ControllerBase:: { ... } | state_ |
Private Member Functions | |
void | commandCB (const std_msgs::Float64MultiArrayConstPtr &msg) |
void | enforceJointLimits (double &command, unsigned int index) |
Private Attributes | |
std::vector< urdf::JointConstSharedPtr > | joint_urdfs_ |
std::vector< control_toolbox::Pid > | pid_controllers_ |
ros::Subscriber | sub_command_ |
Additional Inherited Members | |
Public Types inherited from controller_interface::ControllerBase | |
typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
Protected Member Functions inherited from controller_interface::Controller< hardware_interface::EffortJointInterface > | |
std::string | getHardwareInterfaceType () const |
virtual bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) |
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:
Definition at line 68 of file joint_group_position_controller.h.
effort_controllers::JointGroupPositionController::JointGroupPositionController | ( | ) |
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:
Definition at line 58 of file joint_group_position_controller.cpp.
effort_controllers::JointGroupPositionController::~JointGroupPositionController | ( | ) |
Definition at line 59 of file joint_group_position_controller.cpp.
|
private |
Definition at line 163 of file joint_group_position_controller.cpp.
|
private |
Definition at line 173 of file joint_group_position_controller.cpp.
|
virtual |
Reimplemented from controller_interface::Controller< hardware_interface::EffortJointInterface >.
Definition at line 61 of file joint_group_position_controller.cpp.
|
virtual |
Implements controller_interface::ControllerBase.
Definition at line 121 of file joint_group_position_controller.cpp.
realtime_tools::RealtimeBuffer<std::vector<double> > effort_controllers::JointGroupPositionController::commands_buffer_ |
Definition at line 79 of file joint_group_position_controller.h.
std::vector< std::string > effort_controllers::JointGroupPositionController::joint_names_ |
Definition at line 77 of file joint_group_position_controller.h.
|
private |
Definition at line 87 of file joint_group_position_controller.h.
std::vector< hardware_interface::JointHandle > effort_controllers::JointGroupPositionController::joints_ |
Definition at line 78 of file joint_group_position_controller.h.
unsigned int effort_controllers::JointGroupPositionController::n_joints_ |
Definition at line 80 of file joint_group_position_controller.h.
|
private |
Internal PID controllers.
Definition at line 85 of file joint_group_position_controller.h.
|
private |
Definition at line 83 of file joint_group_position_controller.h.