43 #ifndef VELOCITY_CONTROLLERS__JOINT_POSITION_CONTROLLER_H 44 #define VELOCITY_CONTROLLERS__JOINT_POSITION_CONTROLLER_H 72 #include <boost/scoped_ptr.hpp> 73 #include <boost/thread/condition.hpp> 77 #include <control_msgs/JointControllerState.h> 78 #include <std_msgs/Float64.h> 79 #include <control_msgs/JointControllerState.h> 131 void setCommand(
double pos_target,
double vel_target);
148 void getGains(
double &p,
double &i,
double &d,
double &i_max,
double &i_min);
153 void getGains(
double &p,
double &i,
double &d,
double &i_max,
double &i_min,
bool &antiwindup);
163 void setGains(
const double &p,
const double &i,
const double &d,
const double &i_max,
const double &i_min,
const bool &antiwindup =
false);
194 void setCommandCB(
const std_msgs::Float64ConstPtr& msg);
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
Callback from /command subscriber for setpoint.
~JointPositionController()
control_toolbox::Pid pid_controller_
void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
std::string getJointName()
Get the name of the joint this controller uses.
ros::Subscriber sub_command_
void enforceJointLimits(double &command)
Check that the command is within the hard limits of the joint. Checks for joint type first...
void starting(const ros::Time &time)
This is called from within the realtime thread just before the first call to update.
void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min, const bool &antiwindup=false)
Get the PID parameters.
hardware_interface::JointHandle joint_
double getPosition()
Get the current position of the joint.
bool init(hardware_interface::VelocityJointInterface *robot, ros::NodeHandle &n)
The init function is called to initialize the controller from a non-realtime thread with a pointer to...
JointPositionController()
boost::scoped_ptr< realtime_tools::RealtimePublisher< control_msgs::JointControllerState > > controller_state_publisher_
void setCommand(double pos_target)
Give set position of the joint for next update: revolute (angle) and prismatic (position) ...
realtime_tools::RealtimeBuffer< Commands > command_
void printDebug()
Print debug info to console.
Store position and velocity command in struct to allow easier realtime buffer usage.
urdf::JointConstSharedPtr joint_urdf_
Joint Position Controller.
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
Get the PID parameters.