Go to the documentation of this file.
62 #include <control_msgs/JointControllerState.h>
69 #include <std_msgs/Float64.h>
125 void getGains(
double &p,
double &i,
double &
d,
double &i_max,
double &i_min);
130 void getGains(
double &p,
double &i,
double &
d,
double &i_max,
double &i_min,
bool &antiwindup);
140 void setGains(
const double &p,
const double &i,
const double &
d,
const double &i_max,
const double &i_min,
const bool &antiwindup =
false);
163 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.
JointVelocityController()
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
Callback from /command subscriber for setpoint.
void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
~JointVelocityController()
std::string getJointName()
Get the name of the joint this controller uses.
std::unique_ptr< realtime_tools::RealtimePublisher< control_msgs::JointControllerState > > controller_state_publisher_
void printDebug()
Print debug info to console.
void getCommand(double &cmd)
Get latest velocity command to the joint: revolute (angle) and prismatic (velocity).
Joint Velocity Controller.
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.
void setCommand(double cmd)
Give set velocity of the joint for next update: revolute (angle) and prismatic (velocity)
control_toolbox::Pid pid_controller_
bool init(hardware_interface::EffortJointInterface *robot, const std::string &joint_name, const control_toolbox::Pid &pid)
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
Get the PID parameters.
ros::Subscriber sub_command_
hardware_interface::JointHandle joint_