Public Types | Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
robot Class Reference

#include <robot.h>

Inheritance diagram for robot:
Inheritance graph
[legend]

List of all members.

Public Types

enum  emg_reason { EMG_SERVO_ERROR, EMG_FZ, EMG_SERVO_ALARM, EMG_POWER_OFF }
 reasons of emergency More...

Public Member Functions

bool addJointGroup (const char *gname, const std::vector< std::string > &jnames)
bool checkEmergency (emg_reason &o_reason, int &o_id)
 check occurrence of emergency state
bool checkJointCommands (const double *i_commands)
 check joint commands are valid or not
void disableDisturbanceObserver ()
 disable disturbance observer
void enableDisturbanceObserver ()
 enable disturbance observer
bool init ()
bool init ()
void initializeJointAngle (const char *name, const char *option)
 initialize joint angle
int lengthDigitalInput ()
int lengthDigitalOutput ()
size_t lengthOfExtraServoState (int id)
 get length of extra servo states
bool loadGain ()
 load PD gains
int numBatteries ()
 get the number of batteries
int numThermometers ()
 get the number of thermometers
void oneStep ()
 all processings for one sampling period
bool power (int jid, bool turnon)
 turn on/off power for joint servo
bool power (const char *jname, bool turnon)
 turn on/off power for joint servo
void readAccelerometer (unsigned int i_rank, double *o_accs)
 read accelerometer output
void readBatteryState (unsigned int i_rank, double &o_voltage, double &o_current, double &o_soc)
 read battery state
int readCalibState (int i)
 read calibration status of a joint servo
bool readDigitalInput (char *o_din)
bool readDigitalOutput (char *o_dout)
int readDriverTemperature (int i)
 read temperature of motor driver
void readExtraServoState (int id, int *state)
 read extra servo states
void readForceSensor (unsigned int i_rank, double *o_forces)
 read force sensor output
void readGyroSensor (unsigned int i_rank, double *o_rates)
 read gyro sensor output
void readJointAngles (double *o_angles)
 read array of all joint angles[rad]
void readJointCommands (double *o_commands)
 read array of reference angles of joint servo
int readJointCommandTorques (double *o_torques)
 read array of all commanded joint torques[Nm]
int readJointTorques (double *o_torques)
 read array of all joint torques[Nm]
void readJointVelocities (double *o_velocities)
 read array of all joint velocities[rad/s]
int readPDControllerTorques (double *o_torques)
 read array of all pd controller torques[Nm]
int readPowerState (int i)
 read power status of a joint servo
void readPowerStatus (double &o_voltage, double &o_current)
 read voltage and current of the robot power source
int readServoAlarm (int i)
 read alarm information of a joint servo
int readServoState (int i)
 read servo status of a joint servo
void readThermometer (unsigned int i_rank, double &o_temp)
 read thermometer
void removeForceSensorOffset ()
 remove offsets on force sensor outputs
 robot ()
 constructor
 robot (double dt)
 constructor
bool servo (int jid, bool turnon)
 turn on/off joint servo
bool servo (const char *jname, bool turnon)
 turn on/off joint servo
void setDisturbanceObserverGain (double gain)
 set disturbance observer gain
bool setJointControlMode (const char *i_jname, joint_control_mode mode)
 set control mode of joint
bool setJointInertia (const char *i_jname, double i_mn)
 set joint inertia
void setJointInertias (const double *i_mn)
 set joint inertias
void setProperty (const char *key, const char *value)
bool setServoErrorLimit (const char *i_jname, double i_limit)
 set servo error limit value for specific joint or joint group
bool setServoErrorLimit (const char *i_jname, double i_limit)
 set servo error limit value for specific joint or joint group
bool setServoGainPercentage (const char *i_jname, double i_percentage)
 set the parcentage to the default servo gain
bool setServoTorqueGainPercentage (const char *i_jname, double i_percentage)
 set the parcentage to the default servo torque gain
void startForceSensorCalibration ()
 start force sensor calibration and wait until finish
void startInertiaSensorCalibration ()
 start inertia sensor calibration and wait until finish
void writeAccelerationCommands (const double *i_commands)
 write array of reference accelerations of joint servo
bool writeDigitalOutput (const char *i_dout)
bool writeDigitalOutputWithMask (const char *i_dout, const char *i_mask)
void writeJointCommands (const double *i_commands)
 write array of reference angles of joint servo
void writeTorqueCommands (const double *i_commands)
 write array of reference torques of joint servo
void writeVelocityCommands (const double *i_commands)
 write array of reference velocities of joint servo
 ~robot ()
 destructor
 ~robot ()
 destructor

Public Attributes

double m_accLimit
double m_fzLimitRatio
double m_maxZmpError
std::vector< double > m_servoErrorLimit
double m_servoOnDelay

Private Member Functions

void calibrateForceSensorOneStep ()
 calibrate force sensor for one sampling period
void calibrateInertiaSensorOneStep ()
 calibrate inertia sensor for one sampling period
void gain_control ()
void gain_control (int id)
bool isBusy () const
 check if a calibration process is running or not if one of calibration processes is running, false otherwise
bool names2ids (const std::vector< std::string > &i_names, std::vector< int > &o_ids)

Private Attributes

std::vector< boost::array
< double, 3 > > 
accel_sum
std::vector< boost::array
< double, 3 > > 
att_sum
std::vector< double > default_dgain
std::vector< double > default_pgain
std::vector< double > default_tqdgain
std::vector< double > default_tqpgain
std::vector< double > dgain
int force_calib_counter
std::vector< boost::array
< double, 6 > > 
force_sum
hrp::Vector3 G
std::vector< double > gain_counter
std::vector< boost::array
< double, 3 > > 
gyro_sum
int inertia_calib_counter
std::string m_calibJointName
std::string m_calibOptions
bool m_calibRequested
std::vector< double > m_commandOld
double m_dt
bool m_enable_poweroff_check
std::map< std::string,
std::vector< int > > 
m_jointGroups
int m_lLegForceSensorId
std::string m_pdgainsFilename
bool m_reportedEmergency
int m_rLegForceSensorId
std::vector< double > m_velocityOld
std::vector< double > old_dgain
std::vector< double > old_pgain
std::vector< double > old_tqdgain
std::vector< double > old_tqpgain
std::vector< double > pgain
std::vector< double > tqdgain
std::vector< double > tqpgain
sem_t wait_sem

Detailed Description

Definition at line 12 of file RobotHardware/robot.h.


Member Enumeration Documentation

reasons of emergency

Enumerator:
EMG_SERVO_ERROR 
EMG_FZ 
EMG_SERVO_ALARM 
EMG_POWER_OFF 

Definition at line 254 of file RobotHardware/robot.h.


Constructor & Destructor Documentation

robot::robot ( double  dt)

constructor

Parameters:
dtsampling time

Definition at line 22 of file RobotHardware/robot.cpp.

destructor

Definition at line 28 of file RobotHardware/robot.cpp.

constructor

Definition at line 9 of file SoftErrorLimiter/robot.cpp.

destructor


Member Function Documentation

bool robot::addJointGroup ( const char *  gname,
const std::vector< std::string > &  jnames 
)

Definition at line 892 of file RobotHardware/robot.cpp.

calibrate force sensor for one sampling period

Definition at line 303 of file RobotHardware/robot.cpp.

calibrate inertia sensor for one sampling period

Definition at line 243 of file RobotHardware/robot.cpp.

bool robot::checkEmergency ( emg_reason o_reason,
int o_id 
)

check occurrence of emergency state

Parameters:
o_reasonkind of emergency source
o_idid of sensor/joint of emergency source
Returns:
true if the robot is in emergency state, false otherwise

Definition at line 657 of file RobotHardware/robot.cpp.

bool robot::checkJointCommands ( const double *  i_commands)

check joint commands are valid or not

Returns:
true if the joint command is invalid, false otherwise

Definition at line 622 of file RobotHardware/robot.cpp.

disable disturbance observer

Definition at line 1021 of file RobotHardware/robot.cpp.

enable disturbance observer

Definition at line 1014 of file RobotHardware/robot.cpp.

void robot::gain_control ( ) [private]

Definition at line 345 of file RobotHardware/robot.cpp.

void robot::gain_control ( int  id) [private]

Definition at line 327 of file RobotHardware/robot.cpp.

bool robot::init ( )
bool robot::init ( )

Definition at line 33 of file RobotHardware/robot.cpp.

void robot::initializeJointAngle ( const char *  name,
const char *  option 
)

initialize joint angle

Parameters:
namejoint name, part name or all
optionoptions for initialization

Definition at line 235 of file RobotHardware/robot.cpp.

bool robot::isBusy ( ) const [private]

check if a calibration process is running or not if one of calibration processes is running, false otherwise

Definition at line 488 of file RobotHardware/robot.cpp.

Definition at line 920 of file RobotHardware/robot.cpp.

Definition at line 939 of file RobotHardware/robot.cpp.

get length of extra servo states

Parameters:
idjoint id
Returns:
length of extra servo states

Definition at line 901 of file RobotHardware/robot.cpp.

bool robot::loadGain ( )

load PD gains

Parameters:
fnamename of the file where gains are stored
Returns:
true if gains are loaded successufully, false otherwise

Definition at line 112 of file RobotHardware/robot.cpp.

bool robot::names2ids ( const std::vector< std::string > &  i_names,
std::vector< int > &  o_ids 
) [private]

Definition at line 875 of file RobotHardware/robot.cpp.

get the number of batteries

Returns:
the number of batteries

Definition at line 959 of file RobotHardware/robot.cpp.

get the number of thermometers

Returns:
the number of thermometers

Definition at line 977 of file RobotHardware/robot.cpp.

all processings for one sampling period

Definition at line 351 of file RobotHardware/robot.cpp.

bool robot::power ( int  jid,
bool  turnon 
)

turn on/off power for joint servo

Parameters:
jidjoint id of the joint
turnontrue to turn on power, false otherwise

Definition at line 436 of file RobotHardware/robot.cpp.

bool robot::power ( const char *  jname,
bool  turnon 
)

turn on/off power for joint servo

Parameters:
jnamename of the joint
turnontrue to turn on power, false otherwise

Definition at line 422 of file RobotHardware/robot.cpp.

void robot::readAccelerometer ( unsigned int  i_rank,
double *  o_accs 
)

read accelerometer output

Parameters:
i_rankrank of accelerometer
o_accsarray of accelerations(length = 3)[rad/s^2]

Definition at line 527 of file RobotHardware/robot.cpp.

void robot::readBatteryState ( unsigned int  i_rank,
double &  o_voltage,
double &  o_current,
double &  o_soc 
)

read battery state

Parameters:
i_rankrank of battery
o_voltagevoltage
o_currentcurrent
o_socstate of charge

Definition at line 949 of file RobotHardware/robot.cpp.

read calibration status of a joint servo

Parameters:
ijoint id
Returns:
ON if the joint is already calibrated successfully, OFF otherwise

Definition at line 577 of file RobotHardware/robot.cpp.

bool robot::readDigitalInput ( char *  o_din)

Definition at line 911 of file RobotHardware/robot.cpp.

bool robot::readDigitalOutput ( char *  o_dout)

Definition at line 944 of file RobotHardware/robot.cpp.

read temperature of motor driver

Parameters:
ijoint id
Returns:
0 if temperature can't be measured

Definition at line 605 of file RobotHardware/robot.cpp.

void robot::readExtraServoState ( int  id,
int state 
)

read extra servo states

Parameters:
idjoint id
statearray of int where extra servo states are stored

Definition at line 906 of file RobotHardware/robot.cpp.

void robot::readForceSensor ( unsigned int  i_rank,
double *  o_forces 
)

read force sensor output

Parameters:
i_rankrank of force sensor
o_forcesarray of force/torque(length = 6)[N, Nm]

Definition at line 532 of file RobotHardware/robot.cpp.

void robot::readGyroSensor ( unsigned int  i_rank,
double *  o_rates 
)

read gyro sensor output

Parameters:
i_rankrank of gyro sensor
o_ratesarray of angular velocities(length = 3) [rad/s]

Definition at line 522 of file RobotHardware/robot.cpp.

void robot::readJointAngles ( double *  o_angles)

read array of all joint angles[rad]

Parameters:
o_anglesarray of all joint angles

Definition at line 502 of file RobotHardware/robot.cpp.

void robot::readJointCommands ( double *  o_commands)

read array of reference angles of joint servo

Parameters:
o_commandsarray of reference angles of joint servo[rad]

Definition at line 550 of file RobotHardware/robot.cpp.

int robot::readJointCommandTorques ( double *  o_torques)

read array of all commanded joint torques[Nm]

Parameters:
o_torquesarray of all commanded joint torques
TRUEif read successfully, FALSE otherwise

Definition at line 517 of file RobotHardware/robot.cpp.

int robot::readJointTorques ( double *  o_torques)

read array of all joint torques[Nm]

Parameters:
o_torquesarray of all joint torques
TRUEif read successfully, FALSE otherwise

Definition at line 512 of file RobotHardware/robot.cpp.

void robot::readJointVelocities ( double *  o_velocities)

read array of all joint velocities[rad/s]

Parameters:
o_anglesarray of all joint velocities

Definition at line 507 of file RobotHardware/robot.cpp.

int robot::readPDControllerTorques ( double *  o_torques)

read array of all pd controller torques[Nm]

Parameters:
o_torquesarray of all pd controller torques
TRUEif read successfully, FALSE otherwise

Definition at line 1005 of file RobotHardware/robot.cpp.

read power status of a joint servo

Parameters:
ijoint id
Returns:
ON if power for the joint servo is on, OFF otherwise

Definition at line 584 of file RobotHardware/robot.cpp.

void robot::readPowerStatus ( double &  o_voltage,
double &  o_current 
)

read voltage and current of the robot power source

Parameters:
o_voltagevoltage
o_currentcurrent
o_batteryremaining battery level ( new feature on 315.4.0)

Definition at line 572 of file RobotHardware/robot.cpp.

read alarm information of a joint servo

Parameters:
ijoint id
Returns:
0 if there is no alarm, see iob.h for more details.

Definition at line 598 of file RobotHardware/robot.cpp.

read servo status of a joint servo

Parameters:
ijoint id
Returns:
ON if the joint servo is on, OFF otherwise

Definition at line 591 of file RobotHardware/robot.cpp.

void robot::readThermometer ( unsigned int  i_rank,
double &  o_temp 
)

read thermometer

Parameters:
i_rankrank of thermometer
o_temptemperature

Definition at line 968 of file RobotHardware/robot.cpp.

remove offsets on force sensor outputs

Definition at line 105 of file RobotHardware/robot.cpp.

bool robot::servo ( int  jid,
bool  turnon 
)

turn on/off joint servo

Parameters:
jidjoint id of the joint
turnontrue to turn on joint servo, false otherwise

Definition at line 390 of file RobotHardware/robot.cpp.

bool robot::servo ( const char *  jname,
bool  turnon 
)

turn on/off joint servo

Parameters:
jnamename of the joint
turnontrue to turn on joint servo, false otherwise

Definition at line 364 of file RobotHardware/robot.cpp.

set disturbance observer gain

Parameters:
gaindisturbance observer gain

Definition at line 1028 of file RobotHardware/robot.cpp.

bool robot::setJointControlMode ( const char *  i_jname,
joint_control_mode  mode 
)

set control mode of joint

Parameters:
namejoint name, part name or "all"
modecontrol mode name
Returns:
true if set successfully, false otherwise

Definition at line 1035 of file RobotHardware/robot.cpp.

bool robot::setJointInertia ( const char *  i_jname,
double  i_mn 
)

set joint inertia

Parameters:
i_jnamejoint name
i_mnjoint inertia
Returns:
true if set successfully, false otherwise

Definition at line 986 of file RobotHardware/robot.cpp.

void robot::setJointInertias ( const double *  i_mn)

set joint inertias

Parameters:
i_mnsarray of joint inertia

Definition at line 998 of file RobotHardware/robot.cpp.

void robot::setProperty ( const char *  key,
const char *  value 
)

Definition at line 854 of file RobotHardware/robot.cpp.

bool robot::setServoErrorLimit ( const char *  i_jname,
double  i_limit 
)

set servo error limit value for specific joint or joint group

Parameters:
i_jnamejoint name or joint group name
i_limitnew limit value[rad]
Returns:
true if set successfully, false otherwise
bool robot::setServoErrorLimit ( const char *  i_jname,
double  i_limit 
)

set servo error limit value for specific joint or joint group

Parameters:
i_jnamejoint name or joint group name
i_limitnew limit value[rad]
Returns:
true if set successfully, false otherwise

Definition at line 834 of file RobotHardware/robot.cpp.

bool robot::setServoGainPercentage ( const char *  i_jname,
double  i_percentage 
)

set the parcentage to the default servo gain

Parameters:
namejoint name, part name or "all"
percentageto joint servo gain[0-100]
Returns:
true if set successfully, false otherwise

Definition at line 732 of file RobotHardware/robot.cpp.

bool robot::setServoTorqueGainPercentage ( const char *  i_jname,
double  i_percentage 
)

set the parcentage to the default servo torque gain

Parameters:
namejoint name, part name or "all"
percentageto joint servo gain[0-100]
Returns:
true if set successfully, false otherwise

Definition at line 783 of file RobotHardware/robot.cpp.

start force sensor calibration and wait until finish

Definition at line 218 of file RobotHardware/robot.cpp.

start inertia sensor calibration and wait until finish

Definition at line 181 of file RobotHardware/robot.cpp.

void robot::writeAccelerationCommands ( const double *  i_commands)

write array of reference accelerations of joint servo

Parameters:
i_commandsarray of reference accelerations of joint servo[rad/s]

Definition at line 565 of file RobotHardware/robot.cpp.

bool robot::writeDigitalOutput ( const char *  i_dout)

Definition at line 929 of file RobotHardware/robot.cpp.

bool robot::writeDigitalOutputWithMask ( const char *  i_dout,
const char *  i_mask 
)

Definition at line 934 of file RobotHardware/robot.cpp.

void robot::writeJointCommands ( const double *  i_commands)

write array of reference angles of joint servo

Parameters:
i_commandsarray of reference angles of joint servo[rad]

Definition at line 537 of file RobotHardware/robot.cpp.

void robot::writeTorqueCommands ( const double *  i_commands)

write array of reference torques of joint servo

Parameters:
i_commandsarray of reference torques of joint servo[Nm]

Definition at line 555 of file RobotHardware/robot.cpp.

void robot::writeVelocityCommands ( const double *  i_commands)

write array of reference velocities of joint servo

Parameters:
i_commandsarray of reference velocities of joint servo[rad/s]

Definition at line 560 of file RobotHardware/robot.cpp.


Member Data Documentation

std::vector< boost::array<double,3> > robot::accel_sum [private]

Definition at line 386 of file RobotHardware/robot.h.

std::vector< boost::array<double,3> > robot::att_sum [private]

Definition at line 387 of file RobotHardware/robot.h.

std::vector<double> robot::default_dgain [private]

Definition at line 391 of file RobotHardware/robot.h.

std::vector<double> robot::default_pgain [private]

Definition at line 390 of file RobotHardware/robot.h.

std::vector<double> robot::default_tqdgain [private]

Definition at line 393 of file RobotHardware/robot.h.

std::vector<double> robot::default_tqpgain [private]

Definition at line 392 of file RobotHardware/robot.h.

std::vector<double> robot::dgain [private]

Definition at line 391 of file RobotHardware/robot.h.

Definition at line 382 of file RobotHardware/robot.h.

std::vector< boost::array<double,6> > robot::force_sum [private]

Definition at line 388 of file RobotHardware/robot.h.

Definition at line 404 of file RobotHardware/robot.h.

std::vector<double> robot::gain_counter [private]

Definition at line 383 of file RobotHardware/robot.h.

std::vector< boost::array<double,3> > robot::gyro_sum [private]

Definition at line 385 of file RobotHardware/robot.h.

Definition at line 382 of file RobotHardware/robot.h.

Definition at line 330 of file RobotHardware/robot.h.

std::string robot::m_calibJointName [private]

Definition at line 398 of file RobotHardware/robot.h.

std::string robot::m_calibOptions [private]

Definition at line 398 of file RobotHardware/robot.h.

bool robot::m_calibRequested [private]

Definition at line 397 of file RobotHardware/robot.h.

std::vector<double> robot::m_commandOld [private]

Definition at line 403 of file RobotHardware/robot.h.

double robot::m_dt [private]

Definition at line 402 of file RobotHardware/robot.h.

Definition at line 405 of file RobotHardware/robot.h.

Definition at line 328 of file RobotHardware/robot.h.

std::map<std::string, std::vector<int> > robot::m_jointGroups [private]

Definition at line 396 of file RobotHardware/robot.h.

Definition at line 395 of file RobotHardware/robot.h.

Definition at line 329 of file RobotHardware/robot.h.

std::string robot::m_pdgainsFilename [private]

Definition at line 399 of file RobotHardware/robot.h.

Definition at line 400 of file RobotHardware/robot.h.

Definition at line 395 of file RobotHardware/robot.h.

std::vector< double > robot::m_servoErrorLimit

Definition at line 327 of file RobotHardware/robot.h.

Definition at line 331 of file RobotHardware/robot.h.

std::vector<double> robot::m_velocityOld [private]

Definition at line 403 of file RobotHardware/robot.h.

std::vector<double> robot::old_dgain [private]

Definition at line 391 of file RobotHardware/robot.h.

std::vector<double> robot::old_pgain [private]

Definition at line 390 of file RobotHardware/robot.h.

std::vector<double> robot::old_tqdgain [private]

Definition at line 393 of file RobotHardware/robot.h.

std::vector<double> robot::old_tqpgain [private]

Definition at line 392 of file RobotHardware/robot.h.

std::vector<double> robot::pgain [private]

Definition at line 390 of file RobotHardware/robot.h.

std::vector<double> robot::tqdgain [private]

Definition at line 393 of file RobotHardware/robot.h.

std::vector<double> robot::tqpgain [private]

Definition at line 392 of file RobotHardware/robot.h.

sem_t robot::wait_sem [private]

Definition at line 401 of file RobotHardware/robot.h.


The documentation for this class was generated from the following files:


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Wed May 15 2019 05:02:20