Go to the documentation of this file.
35 #ifndef JOINT_POSITION_CONTROLLER_H
36 #define JOINT_POSITION_CONTROLLER_H
66 #include <boost/scoped_ptr.hpp>
68 #include <std_msgs/Float64.h>
69 #include <pr2_controllers_msgs/JointControllerState.h>
106 void getGains(
double &p,
double &i,
double &d,
double &i_max,
double &i_min);
107 void setGains(
const double &p,
const double &i,
const double &d,
const double &i_max,
const double &i_min);
129 void setCommandCB(
const std_msgs::Float64ConstPtr& msg);
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
JointPositionController()
ros::Subscriber sub_command_
void getCommand(double &cmd)
Get latest position command to the joint: revolute (angle) and prismatic (position).
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
virtual void update()
Issues commands to the joint. Should be called at regular intervals.
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerState > > controller_state_publisher_
std::string getJointName()
pr2_mechanism_model::JointState * joint_state_
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)
void setCommand(double cmd)
Give set position of the joint for next update: revolute (angle) and prismatic (position)
void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min)
control_toolbox::Pid pid_controller_
pr2_mechanism_model::RobotState * robot_
~JointPositionController()