RobotController.h
Go to the documentation of this file.
00001 #ifndef ROBOTCONTROLLER_H
00002 #define ROBOTCONTROLLER_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 "JointController.h"
00013 
00014 #include <boost/thread.hpp>
00015 
00016 #include <ros/ros.h>
00017 
00018 namespace gazebo
00019 {
00020     class RobotController
00021     {
00022     public:
00023         struct JointState
00024         {
00025             double position;
00026             double velocity;
00027             double effort;
00028         };
00029 
00030         RobotController(physics::ModelPtr _modelPtr);
00031         ~RobotController();
00032 
00033         // add/modify joints
00034         void addJoint(physics::JointPtr _jointPtr, bool advancedMode = false);
00035         // child pos/vel/effort scaled to factor * parent
00036         // if child and parent are the same joint, this effectively scales the input for that joint
00037         void addJointDependency(std::string _childName, std::string _parentName, double factor);
00038         void setPosPid(const std::string& name, double _p = 0.0, double _i = 0.0, double _d = 0.0,
00039                     double _imax = 0.0, double _imin = 0.0,
00040                     double _cmdMax = 0.0, double _cmdMin = 0.0);
00041         void setVelPid(const std::string& name, double _p = 0.0, double _i = 0.0, double _d = 0.0,
00042                     double _imax = 0.0, double _imin = 0.0,
00043                     double _cmdMax = 0.0, double _cmdMin = 0.0);
00044 
00045         // move the robot to the specified positions while taking dependencies into account
00046         void setJointPositions(std::map<std::string, double> posMap);
00047         // get states
00048         // if map is empty, get all, ignoring dependent joints
00049         void getJointStates(std::map<std::string, JointState>& posMap);
00050         // get joint targets
00051         // if map is empty, get all, ignoring dependent joints
00052         void getJointTargets(std::map<std::string, JointState>& posMap);
00053 
00054         // get joint limits
00055         // if map is empty, get all, ignoring dependent joints
00056         void getJointLimits(std::map<std::string, std::pair<double, double> >& limitsMap);
00057 
00058         // set targets
00059         void setJointPosTarget(const std::string& name, double target);
00060         void setJointVelTarget(const std::string& name, double target);
00061         void setJointEffortTarget(const std::string& name, double target);
00062 
00063         // joint state management
00064         void setJointControl(const nasa_r2_common_msgs::JointControl::ConstPtr& msg);
00065         const nasa_r2_common_msgs::JointStatus& getJointStatus(const std::string& name) const;
00066         void publishJointStatuses(ros::Publisher& rosPub) const;
00067 
00068         // update PIDs and send forces to joints
00069         void update();
00070 
00071     private:
00072         physics::ModelPtr modelPtr;
00073         std::map<std::string, JointControllerPtr> joints;
00074 
00075         typedef std::multimap<std::string, std::pair<std::string, double> > dependenciesType;
00076         dependenciesType dependencies;
00077 
00078         common::Time prevUpdateTime;
00079     };
00080 }
00081 #endif


gazebo_interface
Author(s): rctaylo2
autogenerated on Mon Oct 6 2014 02:44:38