Go to the documentation of this file.
43 : command_(0), loop_count_(0)
65 std::string joint_name;
66 if (!n.
getParam(
"joint", joint_name)) {
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.
JointHandle getHandle(const std::string &name)
bool getParam(const std::string &key, bool &b) const
~JointVelocityController()
std::string getJointName()
Get the name of the joint this controller uses.
void setCommand(double command)
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.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
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.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
void setCommand(double cmd)
Give set velocity of the joint for next update: revolute (angle) and prismatic (velocity)
std::string getName() const
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.
double getVelocity() const
ros::Subscriber sub_command_
const std::string & getNamespace() const
hardware_interface::JointHandle joint_