35 #ifndef JOINT_GROUP_VELOCITY_CONTROLLER_H 36 #define JOINT_GROUP_VELOCITY_CONTROLLER_H 63 #include <boost/scoped_ptr.hpp> 64 #include <boost/thread/condition.hpp> 71 #include <std_msgs/Float64.h> 72 #include <std_msgs/Float64MultiArray.h> 75 #include <pr2_controllers_msgs/JointControllerState.h> 76 #include <pr2_controllers_msgs/JointControllerStateArray.h> 121 std::vector<pr2_mechanism_model::JointState*>
joints_;
134 void setCommandCB(
const std_msgs::Float64MultiArrayConstPtr& msg);
std::vector< pr2_mechanism_model::JointState * > joints_
std::vector< std::string > getJointName()
virtual void starting()
Issues commands to the joint. Should be called at regular intervals.
void getCommand(std::vector< double > &cmd)
Get latest position command to the joint: revolute (angle) and prismatic (position).
std::vector< control_toolbox::Pid > pid_controllers_
void setCommand(std::vector< double > cmd)
Give set position of the joint for next update: revolute (angle) and prismatic (position) ...
realtime_tools::RealtimeBuffer< std::vector< double > > commands_buffer_
pr2_mechanism_model::RobotState * robot_
ros::Subscriber sub_command_
void getGains(control_toolbox::Pid &pid, double &p, double &i, double &d, double &i_max, double &i_min)
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerStateArray > > controller_state_publisher_
friend class JointGroupVelocityControllerNode
void setCommandCB(const std_msgs::Float64MultiArrayConstPtr &msg)
bool init(pr2_mechanism_model::RobotState *robot, const std::vector< std::string > &joint_names, const control_toolbox::Pid &pid)
JointGroupVelocityController()
~JointGroupVelocityController()