41 #include <control_msgs/JointControllerState.h> 48 #include <std_msgs/Float64MultiArray.h> 77 std::vector< hardware_interface::JointHandle >
joints_;
88 void commandCB(
const std_msgs::Float64MultiArrayConstPtr& msg);
~JointGroupPositionController()
std::vector< hardware_interface::JointHandle > joints_
void commandCB(const std_msgs::Float64MultiArrayConstPtr &msg)
Forward command controller for a set of effort controlled joints (torque or force).
JointGroupPositionController()
Forward command controller for a set of effort controlled joints (torque or force).
void enforceJointLimits(double &command, unsigned int index)
void update(const ros::Time &, const ros::Duration &)
std::vector< std::string > joint_names_
ros::Subscriber sub_command_
std::vector< control_toolbox::Pid > pid_controllers_
realtime_tools::RealtimeBuffer< std::vector< double > > commands_buffer_
std::vector< urdf::JointConstSharedPtr > joint_urdfs_
bool init(hardware_interface::EffortJointInterface *hw, ros::NodeHandle &n)