JointController.h
Go to the documentation of this file.
00001 #ifndef JOINTCONTROLLER_H
00002 #define JOINTCONTROLLER_H
00003 
00004 #include <map>
00005 #include <string>
00006 #include <vector>
00007 
00008 #include "common/PID.hh"
00009 #include "common/Time.hh"
00010 #include "physics/PhysicsTypes.hh"
00011 
00012 #include <boost/thread.hpp>
00013 
00014 #include "r2_msgs/JointStatus.h"
00015 #include "r2_msgs/JointControl.h"
00016 
00017 namespace gazebo
00018 {
00019     class JointController
00020     {
00021     public:
00022         JointController(physics::JointPtr _jointPtr, bool _advancedMode = false);
00023         ~JointController();
00024 
00025         void setPosPid(double _p = 0.0, double _i = 0.0, double _d = 0.0,
00026                     double _imax = 0.0, double _imin = 0.0,
00027                     double _cmdMax = 0.0, double _cmdMin = 0.0);
00028         void setVelPid(double _p = 0.0, double _i = 0.0, double _d = 0.0,
00029                     double _imax = 0.0, double _imin = 0.0,
00030                     double _cmdMax = 0.0, double _cmdMin = 0.0);
00031 
00032         // set targets
00033         void setPosTarget(double target);
00034         void setVelTarget(double target);
00035         void setEffortTarget(double target);
00036 
00037         // update PIDs and send forces to joints
00038         // stepTime is elapsed time since last update
00039         void update(common::Time& stepTime);
00040 
00041         // joint state management
00042         void setJointControl(const r2_msgs::JointControl::ConstPtr& msg);
00043         const r2_msgs::JointStatus& getJointStatus() const;
00044 
00045         void releaseBrake(bool release = true);
00046         void clearFaults();
00047 
00048     private:
00049         physics::JointPtr jointPtr;
00050 
00051         common::PID posPid;
00052         common::PID velPid;
00053 
00054         double position;
00055         double velocity;
00056         double effort;
00057 
00058         boost::mutex controllerMutex;
00059 
00060         bool advancedMode; // use state management stuff below
00061 
00062         // joint state management
00063         enum JointControlMode {POS_COM = 0, TORQ_COM = 1, IMP_COM = 2, VEL_COM = 3};
00064         enum JointFault {OK = 0};
00065 
00066         r2_msgs::JointStatusPtr currStatusPtr;
00067         JointControlMode controlMode;
00068         JointFault fault;
00069 
00070         double jointLowLimit;
00071         double jointHighLimit;
00072     };
00073 
00074     typedef boost::shared_ptr<JointController> JointControllerPtr;
00075 }
00076 #endif


gazebo_interface
Author(s): rctaylo2
autogenerated on Thu Jan 2 2014 11:32:19