6 #include <hrpModel/Sensor.h> 9 #include "hrpsys/io/iob.h" 11 #include "hrpsys/util/Hrpsys.h" 13 #define CALIB_COUNT (10*200) 14 #define GAIN_COUNT ( 5*200) 16 #define DEFAULT_MAX_ZMP_ERROR 0.03 //[m] 17 #define DEFAULT_ANGLE_ERROR_LIMIT 0.2 // [rad] 22 robot::robot(
double dt) : m_fzLimitRatio(0), m_maxZmpError(
DEFAULT_MAX_ZMP_ERROR), m_accLimit(0), m_calibRequested(false), m_pdgainsFilename(
"PDgains.sav"), m_reportedEmergency(true),
m_dt(dt), m_enable_poweroff_check(false),m_servoOnDelay(0)
55 for (
unsigned int i=0; i<
numJoints(); i++){
64 for (
unsigned int i=0; i<
numJoints(); i++){
72 for (
unsigned int i=0; i<
numJoints(); i++){
91 std::cerr <<
"VRML and IOB are inconsistent" << std::endl;
107 std::cerr <<
"[RobotHardware] removeForceSensorOffset..." << std::endl;
109 std::cerr <<
"[RobotHardware] removeForceSensorOffset...done." << std::endl;
115 if (!strm.is_open()) {
123 while ((getlinep = !!(std::getline(strm, str)))) {
133 std::istringstream sstrm(str);
136 if(sstrm.eof())
break;
139 if(sstrm.eof())
break;
143 if(sstrm.eof())
break;
147 if(sstrm.eof())
break;
150 if(sstrm.eof())
break;
159 std::cerr <<
"[RobotHardware] loadGain error: size of gains reading from file (" 161 <<
") does not match size of joints" << std::endl;
169 std::cerr <<
"[RobotHardware] loadGain" << std::endl;
171 std::cerr <<
"[RobotHardware] " <<
joint(
i)->
name 183 std::cerr <<
"[RobotHardware] startInertiaSensorCalibration..." << std::endl;
189 for (
unsigned int j=0;
j<
numSensors(Sensor::RATE_GYRO);
j++) {
190 for (
int i=0;
i<3;
i++) {
196 for(
unsigned int j=0;
j<
numSensors(Sensor::ACCELERATION);
j++) {
197 for (
int i=0;
i<3;
i++) {
204 for(
unsigned int j=0;
j<m_natt;
j++) {
205 for (
int i=0;
i<3;
i++) {
215 std::cerr <<
"[RobotHardware] startInertiaSensorCalibration...done." << std::endl;
225 for (
int i=0;
i<6;
i++) {
246 for (
unsigned int j=0;
j<
numSensors(Sensor::RATE_GYRO);
j++){
249 for (
int i=0;
i<3;
i++)
253 for (
unsigned int j=0;
j<
numSensors(Sensor::ACCELERATION);
j++){
256 for (
int i=0;
i<3;
i++)
261 for (
unsigned int j=0;
j<m_natt;
j++){
264 for (
int i=0;
i<3;
i++)
272 for (
unsigned int j=0;
j<
numSensors(Sensor::RATE_GYRO);
j++) {
273 for (
int i=0;
i<3;
i++) {
279 for (
unsigned int j=0;
j<
numSensors(Sensor::ACCELERATION);
j++) {
283 for (
int i=0;
i<3;
i++) {
290 for (
unsigned int j=0;
j<m_natt;
j++) {
291 for (
int i=0;
i<3;
i++) {
309 for (
int i=0;
i<6;
i++)
316 for (
int i=0;
i<6;
i++) {
329 double new_pgain=0,new_dgain=0,new_tqpgain=0,new_tqdgain=0;
338 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4 339 write_torque_pgain(i, new_tqpgain);
340 write_torque_dgain(i, new_tqdgain);
367 if (strcmp(jname,
"all") == 0 || strcmp(jname,
"ALL") == 0){
370 ret = ret &&
servo(
i, turnon);
375 }
else if ((l =
link(jname))){
378 char *s = (
char *)jname;
while(*s) {*s=toupper(*s);s++;}
380 if (jgroup.size() == 0)
return false;
382 for (
unsigned int i=0;
i<jgroup.size();
i++){
383 ret = ret &&
servo(jgroup[
i], turnon);
404 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4 405 write_torque_pgain(jid, 0);
406 write_torque_dgain(jid, 0);
426 if (strcmp(jname,
"all") == 0 || strcmp(jname,
"ALL") == 0){
430 if (!l)
return false;
433 return power(jid, turnon);
460 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4 461 write_torque_pgain(
i, 0);
462 write_torque_dgain(
i, 0);
474 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4 475 write_torque_pgain(jid, 0);
476 write_torque_dgain(jid, 0);
567 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3 568 write_command_accelerations(i_commands);
607 unsigned char temp=0;
616 struct tm *tm_ = localtime(&tv.tv_sec);
617 static char time[20];
618 sprintf(time,
"%02d:%02d:%02d.%06d", tm_->tm_hour, tm_->tm_min, tm_->tm_sec, (
int)tv.tv_usec);
624 if (!
m_dt)
return false;
632 double v = (command - command_old)/
m_dt;
635 <<
": joint command velocity limit over: joint = " 639 << v/
M_PI*180 <<
"[deg/s]" << std::endl;
645 <<
": joint command acceleration limit over: joint = " 649 << a/
M_PI*180 <<
"[deg/s^2]" << std::endl;
668 <<
": servo error limit over: joint = " 670 <<
", qRef = " << command/
M_PI*180 <<
"[deg], q = " 671 << angle/
M_PI*180 <<
"[deg]" << std::endl;
683 std::cerr <<
time_string() <<
": right Fz limit over: Fz = " << force[
FZ] << std::endl;
693 std::cerr <<
time_string() <<
": left Fz limit over: Fz = " << force[
FZ] << std::endl;
734 if ( i_percentage < 0 || 100 < i_percentage ) {
735 std::cerr <<
"[RobotHardware] Invalid percentage " << i_percentage <<
"[%] for setServoGainPercentage. Percentage should be in (0, 100)[%]." << std::endl;
739 if (strcmp(i_jname,
"all") == 0 || strcmp(i_jname,
"ALL") == 0){
745 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4 751 std::cerr <<
"[RobotHardware] setServoGainPercentage " << i_percentage <<
"[%] for all joints" << std::endl;
752 }
else if ((l =
link(i_jname))){
757 #
if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
762 std::cerr <<
"[RobotHardware] setServoGainPercentage " << i_percentage <<
"[%] for " << i_jname << std::endl;
764 char *s = (
char *)i_jname;
while(*s) {*s=toupper(*s);s++;}
766 if (jgroup.size()==0)
return false;
767 for (
unsigned int i=0;
i<jgroup.size();
i++){
772 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4 778 std::cerr <<
"[RobotHardware] setServoGainPercentage " << i_percentage <<
"[%] for " << i_jname << std::endl;
785 if ( i_percentage < 0 && 100 < i_percentage ) {
786 std::cerr <<
"[RobotHardware] Invalid percentage " << i_percentage <<
"[%] for setServoTorqueGainPercentage. Percentage should be in (0, 100)[%]." << std::endl;
790 if (strcmp(i_jname,
"all") == 0 || strcmp(i_jname,
"ALL") == 0){
792 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4 802 std::cerr <<
"[RobotHardware] setServoTorqueGainPercentage " << i_percentage <<
"[%] for all joints" << std::endl;
803 }
else if ((l =
link(i_jname))){
804 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4 813 std::cerr <<
"[RobotHardware] setServoTorqueGainPercentage " << i_percentage <<
"[%] for " << i_jname << std::endl;
815 char *s = (
char *)i_jname;
while(*s) {*s=toupper(*s);s++;}
817 if (jgroup.size()==0)
return false;
818 for (
unsigned int i=0;
i<jgroup.size();
i++){
819 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4 829 std::cerr <<
"[RobotHardware] setServoTorqueGainPercentage " << i_percentage <<
"[%] for " << i_jname << std::endl;
837 if (strcmp(i_jname,
"all") == 0 || strcmp(i_jname,
"ALL") == 0){
841 }
else if ((l =
link(i_jname))){
844 char *s = (
char *)i_jname;
while(*s) {*s=toupper(*s);s++;}
846 if (jgroup.size()==0)
return false;
847 for (
unsigned int i=0;
i<jgroup.size();
i++){
856 std::istringstream iss(i_value);
857 std::string key(i_key);
858 bool isKnownKey =
true;
859 if (key ==
"sensor_id.right_leg_force_sensor"){
861 }
else if (key ==
"sensor_id.left_leg_force_sensor"){
863 }
else if (key ==
"pdgains.file_name"){
865 }
else if (key ==
"enable_poweroff_check"){
872 if (isKnownKey) std::cout << i_key <<
": " << i_value << std::endl;
876 std::vector<int> &o_ids)
879 for (
unsigned int i=0;
i<i_names.size();
i++){
882 std::cout <<
"joint named [" << i_names[
i] <<
"] not found" 894 char *s = (
char *)gname;
while(*s) {*s=toupper(*s);s++;}
895 std::vector<int> jids;
913 #ifndef NO_DIGITAL_INPUT 922 #ifndef NO_DIGITAL_INPUT 950 double ¤t,
double &soc)
952 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2 953 read_battery(i_rank, &voltage, ¤t, &soc);
955 voltage=0; current=0; soc=0;
961 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2 962 return number_of_batteries();
970 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2 979 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2 980 return number_of_thermometers();
988 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3 990 if (!l)
return false;
992 return write_joint_inertia(jid, mn);
1000 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3 1001 write_joint_inertias(mns);
1007 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3 1008 return read_pd_controller_torques(o_torques);
1016 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3 1017 write_disturbance_observer(
ON);
1023 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3 1024 write_disturbance_observer(
OFF);
1030 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3 1031 write_disturbance_observer_gain(gain);
1038 if (strcmp(i_jname,
"all") == 0 || strcmp(i_jname,
"ALL") == 0) {
1042 std::cerr <<
"[RobotHardware] setJointControlMode for all joints : " << mode << std::endl;
1043 }
else if ((l =
link(i_jname))) {
1045 std::cerr <<
"[RobotHardware] setJointControlMode for " << i_jname <<
" : " << mode << std::endl;
1047 char *s = (
char *)i_jname;
while(*s) { *s=toupper(*s); s++; }
1049 if (jgroup.size()==0)
return false;
1050 for (
unsigned int i=0;
i<jgroup.size();
i++) {
1053 std::cerr <<
"[RobotHardware] setJointControlMode for " << i_jname <<
" : " << mode << std::endl;
void oneStep()
all processings for one sampling period
int write_dgain(int id, double gain)
write D gain[Nm/(rad/s)]
int read_servo_state(int id, int *s)
read servo status
std::vector< double > dgain
void enableDisturbanceObserver()
enable disturbance observer
int read_attitude_sensor(int id, double *att)
read output of attitude sensor
std::vector< double > m_commandOld
int write_power_command(int id, int com)
turn on/off power supply for motor driver
int read_command_angle(int id, double *angle)
read command angle[rad]
void readThermometer(unsigned int i_rank, double &o_temp)
read thermometer
std::vector< double > tqdgain
int set_number_of_gyro_sensors(int num)
set the number of gyro sensors
int read_dgain(int id, double *gain)
read D gain[Nm/(rad/s)]
int read_calib_state(int id, int *s)
read callibration state of joint
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
int read_command_torques(double *torques)
read array of command torques[Nm]
std::vector< double > pgain
int read_extra_servo_state(int id, int *state)
read extra servo states
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)
int write_digital_output_with_mask(const char *doutput, const char *mask)
write_digital_output, non-applicable bits are nop
std::vector< double > gain_counter
void startForceSensorCalibration()
start force sensor calibration and wait until finish
int close_iob(void)
close connection with joint servo process
int read_force_sensor(int id, double *forces)
read output of force sensor
int number_of_accelerometers()
get the number of accelerometers
RTC::ReturnCode_t ret(RTC::Local::ReturnCode_t r)
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 read_power(double *voltage, double *current)
read status of power source
int readServoState(int i)
read servo status of a joint servo
std::vector< double > old_dgain
int number_of_gyro_sensors()
get the number of gyro sensors
std::vector< boost::array< double, 3 > > gyro_sum
std::vector< double > default_pgain
int read_actual_angle(int id, double *angle)
read current joint angle[rad]
int open_iob(void)
open connection with joint servo process
unsigned int numSensors(int sensorType) const
int write_control_mode(int id, joint_control_mode s)
write joint control mode
int length_digital_input()
get_digital_input_length
int write_gyro_sensor_offset(int id, double *offset)
write offset values for gyro sensor output
void setJointInertias(const double *i_mn)
set joint inertias
int readDriverTemperature(int i)
read temperature of motor driver
size_t length_of_extra_servo_state(int id)
get length of extra servo states
int length_digital_output()
get_digital_output_length
int read_power_state(int id, int *s)
read power status of motor driver
std::map< std::string, std::vector< int > > m_jointGroups
int read_command_angles(double *angles)
read array of command angles[rad]
int write_pgain(int id, double gain)
write P gain[Nm/rad]
int set_number_of_accelerometers(int num)
set the number of accelerometers
int gettimeofday(struct timeval *tv, struct timezone *tz)
int write_attitude_sensor_offset(int id, double *offset)
std::string m_pdgainsFilename
bool isBusy() const
check if a calibration process is running or not if one of calibration processes is running...
def j(str, encoding="cp932")
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)
int write_digital_output(const char *doutput)
write_digital_output, non-applicable bits are nop
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 read_actual_velocities(double *vels)
read actual angular velocities[rad/s]
int read_gyro_sensor(int id, double *rates)
read output of gyro sensor
int number_of_force_sensors()
get the number of force sensors
emg_reason
reasons of emergency
int number_of_joints()
get the number of joints
int read_driver_temperature(int id, unsigned char *v)
read temperature of motor driver[Celsius]
void startInertiaSensorCalibration()
start inertia sensor calibration and wait until finish
void readAccelerometer(unsigned int i_rank, double *o_accs)
read accelerometer output
int read_temperature(int id, double *v)
read thermometer
int readPDControllerTorques(double *o_torques)
read array of all pd controller torques[Nm]
Link * joint(int id) const
bool checkEmergency(emg_reason &o_reason, int &o_id)
check occurrence of emergency state
int read_accelerometer(int id, double *accels)
read output of accelerometer
void writeJointCommands(const double *i_commands)
write array of reference angles of joint servo
Link * link(int index) const
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
int write_force_offset(int id, double *offsets)
write offset values for force sensor output
int readServoAlarm(int i)
read alarm information of a joint servo
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)
std::string sprintf(char const *__restrict fmt,...)
void readGyroSensor(unsigned int i_rank, double *o_rates)
read gyro sensor output
std::vector< double > m_servoErrorLimit
std::vector< double > tqpgain
unsigned int numJoints() const
int read_servo_alarm(int id, int *a)
read servo alarms
int readJointCommandTorques(double *o_torques)
read array of all commanded joint torques[Nm]
int read_digital_output(char *doutput)
read_digital_output, non-applicable bits are nop
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 read_digital_input(char *dinput)
read_digital_input, non-applicable bits are nop
bool loadGain()
load PD gains
int set_number_of_joints(int num)
set the number of joints
#define DEFAULT_ANGLE_ERROR_LIMIT
void removeForceSensorOffset()
remove offsets on force sensor outputs
bool power(int jid, bool turnon)
turn on/off power for joint servo
static std::vector< double > command
size_t lengthOfExtraServoState(int id)
get length of extra servo states
int write_servo(int id, int com)
turn on/off joint servo
int inertia_calib_counter
bool m_enable_poweroff_check
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
int set_number_of_force_sensors(int num)
set the number of force sensors
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]
int write_command_velocities(const double *vels)
write command angular velocities[rad/s]
void writeTorqueCommands(const double *i_commands)
write array of reference torques of joint servo
Sensor * sensor(int sensorType, int sensorId) const
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
int write_command_angle(int id, double angle)
write command angle[rad]
int read_actual_angles(double *angles)
read array of current joint angles[rad]
int usleep(useconds_t usec)
void disableDisturbanceObserver()
disable disturbance observer
int write_command_torques(const double *torques)
write array of command torques[Nm]
int write_command_angles(const double *angles)
write array of command angles[rad]
int read_actual_torques(double *torques)
read array of current joint torques[Nm]
#define DEFAULT_MAX_ZMP_ERROR
int read_pgain(int id, double *gain)
read P gain[Nm/rad]
int write_accelerometer_offset(int id, double *offset)
write offset values for accelerometer output