35 #ifndef JOINT_VELOCITY_CONTROLLER_H 36 #define JOINT_VELOCITY_CONTROLLER_H 63 #include <boost/scoped_ptr.hpp> 64 #include <boost/thread/condition.hpp> 71 #include <std_msgs/Float64.h> 74 #include <pr2_controllers_msgs/JointControllerState.h> 112 void getGains(
double &p,
double &i,
double &
d,
double &i_max,
double &i_min);
113 void setGains(
const double &p,
const double &i,
const double &d,
const double &i_max,
const double &i_min);
134 void setCommandCB(
const std_msgs::Float64ConstPtr& msg);
pr2_mechanism_model::JointState * joint_state_
void getCommand(double &cmd)
Get latest position command to the joint: revolute (angle) and prismatic (position).
friend class JointVelocityControllerNode
ros::Subscriber sub_command_
~JointVelocityController()
pr2_mechanism_model::RobotState * robot_
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
void setCommand(double cmd)
Give set position of the joint for next update: revolute (angle) and prismatic (position) ...
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerState > > controller_state_publisher_
JointVelocityController()
virtual void starting()
Issues commands to the joint. Should be called at regular intervals.
control_toolbox::Pid pid_controller_
void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min)
std::string getJointName()
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)