Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #ifndef EFFORT_CONTROLLERS__JOINT_VELOCITY_CONTROLLER_H
00037 #define EFFORT_CONTROLLERS__JOINT_VELOCITY_CONTROLLER_H
00038
00062 #include <ros/node_handle.h>
00063 #include <boost/thread/condition.hpp>
00064 #include <boost/scoped_ptr.hpp>
00065 #include <hardware_interface/joint_command_interface.h>
00066 #include <controller_interface/controller.h>
00067 #include <control_msgs/JointControllerState.h>
00068 #include <std_msgs/Float64.h>
00069 #include <control_toolbox/pid.h>
00070 #include <realtime_tools/realtime_publisher.h>
00071
00072 namespace effort_controllers
00073 {
00074
00075 class JointVelocityController: public controller_interface::Controller<hardware_interface::EffortJointInterface>
00076 {
00077 public:
00078
00079 JointVelocityController();
00080 ~JointVelocityController();
00081
00082 bool init(hardware_interface::EffortJointInterface *robot, const std::string &joint_name, const control_toolbox::Pid &pid);
00083
00097 bool init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n);
00098
00104 void setCommand(double cmd);
00105
00109 void getCommand(double & cmd);
00110
00116 void starting(const ros::Time& time);
00117
00121 void update(const ros::Time& time, const ros::Duration& period);
00122
00126 void getGains(double &p, double &i, double &d, double &i_max, double &i_min);
00127
00131 void printDebug();
00132
00136 void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min);
00137
00141 std::string getJointName();
00142
00143 hardware_interface::JointHandle joint_;
00144 double command_;
00146 private:
00147 int loop_count_;
00148 control_toolbox::Pid pid_controller_;
00150
00151
00152 boost::scoped_ptr<
00153 realtime_tools::RealtimePublisher<
00154 control_msgs::JointControllerState> > controller_state_publisher_ ;
00155
00156 ros::Subscriber sub_command_;
00157
00161 void setCommandCB(const std_msgs::Float64ConstPtr& msg);
00162 };
00163
00164 }
00165
00166 #endif