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
00037
00038
00039
00040
00041
00042
00043 #ifndef VELOCITY_CONTROLLERS__JOINT_POSITION_CONTROLLER_H
00044 #define VELOCITY_CONTROLLERS__JOINT_POSITION_CONTROLLER_H
00045
00069 #include <ros/node_handle.h>
00070 #include <urdf/model.h>
00071 #include <control_toolbox/pid.h>
00072 #include <boost/scoped_ptr.hpp>
00073 #include <boost/thread/condition.hpp>
00074 #include <realtime_tools/realtime_publisher.h>
00075 #include <hardware_interface/joint_command_interface.h>
00076 #include <controller_interface/controller.h>
00077 #include <control_msgs/JointControllerState.h>
00078 #include <std_msgs/Float64.h>
00079 #include <control_msgs/JointControllerState.h>
00080 #include <realtime_tools/realtime_buffer.h>
00081
00082 namespace velocity_controllers
00083 {
00084
00085 class JointPositionController: public controller_interface::Controller<hardware_interface::VelocityJointInterface>
00086 {
00087 public:
00088
00092 struct Commands
00093 {
00094 double position_;
00095 double velocity_;
00096 bool has_velocity_;
00097 };
00098
00099 JointPositionController();
00100 ~JointPositionController();
00101
00115 bool init(hardware_interface::VelocityJointInterface *robot, ros::NodeHandle &n);
00116
00122 void setCommand(double pos_target);
00123
00131 void setCommand(double pos_target, double vel_target);
00132
00138 void starting(const ros::Time& time);
00139
00143 void update(const ros::Time& time, const ros::Duration& period);
00144
00148 void getGains(double &p, double &i, double &d, double &i_max, double &i_min);
00149
00153 void printDebug();
00154
00158 void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min);
00159
00163 std::string getJointName();
00164
00169 double getPosition();
00170
00171 hardware_interface::JointHandle joint_;
00172 boost::shared_ptr<const urdf::Joint> joint_urdf_;
00173 realtime_tools::RealtimeBuffer<Commands> command_;
00174 Commands command_struct_;
00175
00176 private:
00177 int loop_count_;
00178 control_toolbox::Pid pid_controller_;
00180 boost::scoped_ptr<
00181 realtime_tools::RealtimePublisher<
00182 control_msgs::JointControllerState> > controller_state_publisher_ ;
00183
00184 ros::Subscriber sub_command_;
00185
00189 void setCommandCB(const std_msgs::Float64ConstPtr& msg);
00190
00196 void enforceJointLimits(double &command);
00197
00198 };
00199
00200 }
00201
00202 #endif