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