robot.h
Go to the documentation of this file.
00001 #ifndef __ROBOT_H__
00002 #define __ROBOT_H__
00003 
00004 #include <boost/array.hpp>
00005 #include <semaphore.h>
00006 #include <hrpModel/Body.h>
00007 
00011 class robot : public hrp::Body
00012 {
00013 public:
00018     robot(double dt);
00019 
00023     ~robot();
00024 
00028     bool init();
00029 
00035     bool servo(int jid, bool turnon);
00036 
00042     bool servo(const char *jname, bool turnon);
00043 
00049     bool power(int jid, bool turnon);
00050 
00056     bool power(const char *jname, bool turnon);
00057 
00061     void removeForceSensorOffset();
00062 
00068     bool loadGain();
00069 
00073     void startInertiaSensorCalibration();
00074 
00078     void startForceSensorCalibration();
00079 
00085     void initializeJointAngle(const char *name, const char *option);
00086 
00090     void oneStep();
00091 
00097     int readCalibState(int i);
00098 
00104     int readPowerState(int i);
00105 
00111     int readServoState(int i);
00112 
00118     int readServoAlarm(int i);
00119 
00125     int readDriverTemperature(int i);
00126 
00133     void readPowerStatus(double &o_voltage, double &o_current);
00134 
00142     void readBatteryState(unsigned int i_rank, double &o_voltage,
00143                           double &o_current, double &o_soc);
00144 
00150     void readThermometer(unsigned int i_rank, double &o_temp);
00151 
00156     void readJointAngles(double *o_angles);
00157 
00162     void readJointVelocities(double *o_velocities);
00163 
00169     int readJointTorques(double *o_torques);
00170 
00176     int readJointCommandTorques(double *o_torques);
00177 
00183     void readGyroSensor(unsigned int i_rank, double *o_rates);
00184 
00190     void readAccelerometer(unsigned int i_rank, double *o_accs);
00191 
00197     void readForceSensor(unsigned int i_rank, double *o_forces);
00198 
00203     void writeJointCommands(const double *i_commands);
00204 
00209     void readJointCommands(double *o_commands);
00210 
00215     void writeTorqueCommands(const double *i_commands);
00216 
00221     void writeVelocityCommands(const double *i_commands);
00222 
00228     size_t lengthOfExtraServoState(int id);
00229 
00235     void readExtraServoState(int id, int *state);
00236 
00240     typedef enum {EMG_SERVO_ERROR, EMG_FZ, EMG_SERVO_ALARM, EMG_POWER_OFF} emg_reason;
00241 
00248     bool checkEmergency(emg_reason &o_reason, int &o_id);
00249 
00250 
00255     bool checkJointCommands(const double *i_commands);
00256 
00263     bool setServoGainPercentage(const char *i_jname, double i_percentage);
00264 
00271     bool setServoErrorLimit(const char *i_jname, double i_limit);
00272 
00273     void setProperty(const char *key, const char *value);
00274     bool addJointGroup(const char *gname, const std::vector<std::string>& jnames);
00275     std::vector<double> m_servoErrorLimit;  
00276     double m_fzLimitRatio;
00277     double m_maxZmpError;
00278     double m_accLimit;
00279 
00280     bool readDigitalInput(char *o_din);
00281     int lengthDigitalInput();
00282     bool writeDigitalOutput(const char *i_dout);
00283     bool writeDigitalOutputWithMask(const char *i_dout, const char *i_mask);
00284     int lengthDigitalOutput();
00285     bool readDigitalOutput(char *o_dout);
00286 
00291     int numBatteries();
00292 
00297     int numThermometers();
00298 private:
00302     void calibrateInertiaSensorOneStep();
00303 
00307     void calibrateForceSensorOneStep();
00308 
00313     bool isBusy() const;
00314 
00315     bool names2ids(const std::vector<std::string> &i_names, 
00316                    std::vector<int> &o_ids);
00317 
00318     void gain_control();
00319     void gain_control(int id);
00320 
00321     int inertia_calib_counter, force_calib_counter;
00322     std::vector<double> gain_counter;
00323 
00324     std::vector< boost::array<double,3> > gyro_sum;
00325     std::vector< boost::array<double,3> > accel_sum;
00326     std::vector< boost::array<double,3> > att_sum;
00327     std::vector< boost::array<double,6> > force_sum;
00328 
00329     std::vector<double> pgain, old_pgain, default_pgain;
00330     std::vector<double> dgain, old_dgain, default_dgain;
00331 
00332     int m_lLegForceSensorId, m_rLegForceSensorId;
00333     std::map<std::string, std::vector<int> > m_jointGroups;
00334     bool m_calibRequested;
00335     std::string m_calibJointName, m_calibOptions;
00336     std::string m_pdgainsFilename;
00337     bool m_reportedEmergency;
00338     sem_t wait_sem;
00339     double m_dt;
00340     std::vector<double> m_commandOld, m_velocityOld;
00341     hrp::Vector3 G;
00342     bool m_enable_poweroff_check;
00343 };
00344 
00345 #endif


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Wed Sep 6 2017 02:35:55