RobotHardware/robot.h
Go to the documentation of this file.
1 #ifndef __ROBOT_H__
2 #define __ROBOT_H__
3 
4 #include <boost/array.hpp>
5 #include <semaphore.h>
6 #include <hrpModel/Body.h>
7 #include "hrpsys/io/iob.h"
8 
12 class robot : public hrp::Body
13 {
14 public:
19  robot(double dt);
20 
24  ~robot();
25 
29  bool init();
30 
36  bool servo(int jid, bool turnon);
37 
43  bool servo(const char *jname, bool turnon);
44 
50  bool power(int jid, bool turnon);
51 
57  bool power(const char *jname, bool turnon);
58 
63 
69  bool loadGain();
70 
75 
80 
86  void initializeJointAngle(const char *name, const char *option);
87 
91  void oneStep();
92 
98  int readCalibState(int i);
99 
105  int readPowerState(int i);
106 
112  int readServoState(int i);
113 
119  int readServoAlarm(int i);
120 
126  int readDriverTemperature(int i);
127 
134  void readPowerStatus(double &o_voltage, double &o_current);
135 
143  void readBatteryState(unsigned int i_rank, double &o_voltage,
144  double &o_current, double &o_soc);
145 
151  void readThermometer(unsigned int i_rank, double &o_temp);
152 
157  void readJointAngles(double *o_angles);
158 
163  void readJointVelocities(double *o_velocities);
164 
170  int readJointTorques(double *o_torques);
171 
177  int readJointCommandTorques(double *o_torques);
178 
184  void readGyroSensor(unsigned int i_rank, double *o_rates);
185 
191  void readAccelerometer(unsigned int i_rank, double *o_accs);
192 
198  void readForceSensor(unsigned int i_rank, double *o_forces);
199 
204  void writeJointCommands(const double *i_commands);
205 
210  void readJointCommands(double *o_commands);
211 
216  void writeTorqueCommands(const double *i_commands);
217 
222  void writeVelocityCommands(const double *i_commands);
223 
228  void writeAccelerationCommands(const double *i_commands);
229 
235  int readPDControllerTorques(double *o_torques);
236 
242  size_t lengthOfExtraServoState(int id);
243 
249  void readExtraServoState(int id, int *state);
250 
255 
262  bool checkEmergency(emg_reason &o_reason, int &o_id);
263 
264 
269  bool checkJointCommands(const double *i_commands);
270 
277  bool setServoGainPercentage(const char *i_jname, double i_percentage);
278 
285  bool setServoTorqueGainPercentage(const char *i_jname, double i_percentage);
286 
293  bool setServoErrorLimit(const char *i_jname, double i_limit);
294 
301  bool setJointInertia(const char *i_jname, double i_mn);
302 
307  void setJointInertias(const double *i_mn);
308 
313 
318 
323  void setDisturbanceObserverGain(double gain);
324 
325  void setProperty(const char *key, const char *value);
326  bool addJointGroup(const char *gname, const std::vector<std::string>& jnames);
327  std::vector<double> m_servoErrorLimit;
330  double m_accLimit;
332 
333  bool readDigitalInput(char *o_din);
334  int lengthDigitalInput();
335  bool writeDigitalOutput(const char *i_dout);
336  bool writeDigitalOutputWithMask(const char *i_dout, const char *i_mask);
337  int lengthDigitalOutput();
338  bool readDigitalOutput(char *o_dout);
339 
344  int numBatteries();
345 
350  int numThermometers();
351 
358  bool setJointControlMode(const char *i_jname, joint_control_mode mode);
359 private:
364 
369 
374  bool isBusy() const;
375 
376  bool names2ids(const std::vector<std::string> &i_names,
377  std::vector<int> &o_ids);
378 
379  void gain_control();
380  void gain_control(int id);
381 
383  std::vector<double> gain_counter;
384 
385  std::vector< boost::array<double,3> > gyro_sum;
386  std::vector< boost::array<double,3> > accel_sum;
387  std::vector< boost::array<double,3> > att_sum;
388  std::vector< boost::array<double,6> > force_sum;
389 
390  std::vector<double> pgain, old_pgain, default_pgain;
391  std::vector<double> dgain, old_dgain, default_dgain;
392  std::vector<double> tqpgain, old_tqpgain, default_tqpgain;
393  std::vector<double> tqdgain, old_tqdgain, default_tqdgain;
394 
396  std::map<std::string, std::vector<int> > m_jointGroups;
399  std::string m_pdgainsFilename;
401  sem_t wait_sem;
402  double m_dt;
403  std::vector<double> m_commandOld, m_velocityOld;
406 };
407 
408 #endif
void oneStep()
all processings for one sampling period
std::vector< double > dgain
void enableDisturbanceObserver()
enable disturbance observer
std::vector< double > m_commandOld
void readThermometer(unsigned int i_rank, double &o_temp)
read thermometer
std::vector< double > tqdgain
bool servo(int jid, bool turnon)
turn on/off joint servo
std::vector< double > old_pgain
void readPowerStatus(double &o_voltage, double &o_current)
read voltage and current of the robot power source
std::string m_calibJointName
state
std::vector< double > pgain
void writeVelocityCommands(const double *i_commands)
write array of reference velocities of joint servo
int numBatteries()
get the number of batteries
bool readDigitalInput(char *o_din)
double m_accLimit
std::vector< double > gain_counter
void startForceSensorCalibration()
start force sensor calibration and wait until finish
double m_servoOnDelay
png_voidp int value
int readPowerState(int i)
read power status of a joint servo
std::vector< boost::array< double, 6 > > force_sum
std::vector< boost::array< double, 3 > > att_sum
bool checkJointCommands(const double *i_commands)
check joint commands are valid or not
void calibrateForceSensorOneStep()
calibrate force sensor for one sampling period
int readServoState(int i)
read servo status of a joint servo
std::vector< double > old_dgain
std::vector< boost::array< double, 3 > > gyro_sum
bool m_calibRequested
std::vector< double > default_pgain
png_uint_32 i
JCOPY_OPTION option
bool m_reportedEmergency
void setJointInertias(const double *i_mn)
set joint inertias
~robot()
destructor
int readDriverTemperature(int i)
read temperature of motor driver
Eigen::Vector3d Vector3
std::map< std::string, std::vector< int > > m_jointGroups
std::string m_pdgainsFilename
bool isBusy() const
check if a calibration process is running or not if one of calibration processes is running...
const std::string & name()
bool names2ids(const std::vector< std::string > &i_names, std::vector< int > &o_ids)
void setProperty(const char *key, const char *value)
void readJointCommands(double *o_commands)
read array of reference angles of joint servo
std::vector< boost::array< double, 3 > > accel_sum
std::vector< double > m_velocityOld
int m_lLegForceSensorId
emg_reason
reasons of emergency
int m_rLegForceSensorId
void startInertiaSensorCalibration()
start inertia sensor calibration and wait until finish
void readAccelerometer(unsigned int i_rank, double *o_accs)
read accelerometer output
robot()
constructor
int readPDControllerTorques(double *o_torques)
read array of all pd controller torques[Nm]
bool checkEmergency(emg_reason &o_reason, int &o_id)
check occurrence of emergency state
void writeJointCommands(const double *i_commands)
write array of reference angles of joint servo
bool addJointGroup(const char *gname, const std::vector< std::string > &jnames)
bool setJointControlMode(const char *i_jname, joint_control_mode mode)
set control mode of joint
double m_maxZmpError
int readServoAlarm(int i)
read alarm information of a joint servo
int force_calib_counter
std::vector< double > default_dgain
void writeAccelerationCommands(const double *i_commands)
write array of reference accelerations of joint servo
void readJointVelocities(double *o_velocities)
read array of all joint velocities[rad/s]
int numThermometers()
get the number of thermometers
bool writeDigitalOutput(const char *i_dout)
void readGyroSensor(unsigned int i_rank, double *o_rates)
read gyro sensor output
std::vector< double > tqpgain
std::vector< double > m_servoErrorLimit
joint_control_mode
Definition: iob.h:61
int readJointCommandTorques(double *o_torques)
read array of all commanded joint torques[Nm]
int readCalibState(int i)
read calibration status of a joint servo
bool readDigitalOutput(char *o_dout)
std::vector< double > old_tqpgain
int lengthDigitalOutput()
bool setServoGainPercentage(const char *i_jname, double i_percentage)
set the parcentage to the default servo gain
bool writeDigitalOutputWithMask(const char *i_dout, const char *i_mask)
void readExtraServoState(int id, int *state)
read extra servo states
std::vector< double > default_tqpgain
void setDisturbanceObserverGain(double gain)
set disturbance observer gain
bool setServoErrorLimit(const char *i_jname, double i_limit)
set servo error limit value for specific joint or joint group
std::vector< double > default_tqdgain
int lengthDigitalInput()
bool loadGain()
load PD gains
void removeForceSensorOffset()
remove offsets on force sensor outputs
bool power(int jid, bool turnon)
turn on/off power for joint servo
size_t lengthOfExtraServoState(int id)
get length of extra servo states
int inertia_calib_counter
bool m_enable_poweroff_check
void gain_control()
bool setServoTorqueGainPercentage(const char *i_jname, double i_percentage)
set the parcentage to the default servo torque gain
void readJointAngles(double *o_angles)
read array of all joint angles[rad]
void calibrateInertiaSensorOneStep()
calibrate inertia sensor for one sampling period
void initializeJointAngle(const char *name, const char *option)
initialize joint angle
std::vector< double > old_tqdgain
void readForceSensor(unsigned int i_rank, double *o_forces)
read force sensor output
std::string m_calibOptions
int readJointTorques(double *o_torques)
read array of all joint torques[Nm]
void writeTorqueCommands(const double *i_commands)
write array of reference torques of joint servo
double m_fzLimitRatio
void readBatteryState(unsigned int i_rank, double &o_voltage, double &o_current, double &o_soc)
read battery state
bool setJointInertia(const char *i_jname, double i_mn)
set joint inertia
void disableDisturbanceObserver()
disable disturbance observer
hrp::Vector3 G


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Thu May 6 2021 02:41:51