Public Types | Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
robot Class Reference

#include <robot.h>

Inheritance diagram for robot:
Inheritance graph
[legend]

Public Types

enum  emg_reason { EMG_SERVO_ERROR, EMG_FZ, EMG_SERVO_ALARM, EMG_POWER_OFF }
 reasons of emergency More...
 
- Public Types inherited from hrp::Body
enum  ExtraJointType
 

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 More...
 
bool checkJointCommands (const double *i_commands)
 check joint commands are valid or not More...
 
void disableDisturbanceObserver ()
 disable disturbance observer More...
 
void enableDisturbanceObserver ()
 enable disturbance observer More...
 
bool init ()
 
bool init ()
 
void initializeJointAngle (const char *name, const char *option)
 initialize joint angle More...
 
int lengthDigitalInput ()
 
int lengthDigitalOutput ()
 
size_t lengthOfExtraServoState (int id)
 get length of extra servo states More...
 
bool loadGain ()
 load PD gains More...
 
int numBatteries ()
 get the number of batteries More...
 
int numThermometers ()
 get the number of thermometers More...
 
void oneStep ()
 all processings for one sampling period More...
 
bool power (int jid, bool turnon)
 turn on/off power for joint servo More...
 
bool power (const char *jname, bool turnon)
 turn on/off power for joint servo More...
 
void readAccelerometer (unsigned int i_rank, double *o_accs)
 read accelerometer output More...
 
void readBatteryState (unsigned int i_rank, double &o_voltage, double &o_current, double &o_soc)
 read battery state More...
 
int readCalibState (int i)
 read calibration status of a joint servo More...
 
bool readDigitalInput (char *o_din)
 
bool readDigitalOutput (char *o_dout)
 
int readDriverTemperature (int i)
 read temperature of motor driver More...
 
void readExtraServoState (int id, int *state)
 read extra servo states More...
 
void readForceSensor (unsigned int i_rank, double *o_forces)
 read force sensor output More...
 
void readGyroSensor (unsigned int i_rank, double *o_rates)
 read gyro sensor output More...
 
void readJointAngles (double *o_angles)
 read array of all joint angles[rad] More...
 
void readJointCommands (double *o_commands)
 read array of reference angles of joint servo More...
 
int readJointCommandTorques (double *o_torques)
 read array of all commanded joint torques[Nm] More...
 
int readJointTorques (double *o_torques)
 read array of all joint torques[Nm] More...
 
void readJointVelocities (double *o_velocities)
 read array of all joint velocities[rad/s] More...
 
int readPDControllerTorques (double *o_torques)
 read array of all pd controller torques[Nm] More...
 
int readPowerState (int i)
 read power status of a joint servo More...
 
void readPowerStatus (double &o_voltage, double &o_current)
 read voltage and current of the robot power source More...
 
int readServoAlarm (int i)
 read alarm information of a joint servo More...
 
int readServoState (int i)
 read servo status of a joint servo More...
 
void readThermometer (unsigned int i_rank, double &o_temp)
 read thermometer More...
 
void removeForceSensorOffset ()
 remove offsets on force sensor outputs More...
 
 robot ()
 constructor More...
 
 robot (double dt)
 constructor More...
 
bool servo (int jid, bool turnon)
 turn on/off joint servo More...
 
bool servo (const char *jname, bool turnon)
 turn on/off joint servo More...
 
void setDisturbanceObserverGain (double gain)
 set disturbance observer gain More...
 
bool setJointControlMode (const char *i_jname, joint_control_mode mode)
 set control mode of joint More...
 
bool setJointInertia (const char *i_jname, double i_mn)
 set joint inertia More...
 
void setJointInertias (const double *i_mn)
 set joint inertias More...
 
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 More...
 
bool setServoErrorLimit (const char *i_jname, double i_limit)
 set servo error limit value for specific joint or joint group More...
 
bool setServoGainPercentage (const char *i_jname, double i_percentage)
 set the parcentage to the default servo gain More...
 
bool setServoTorqueGainPercentage (const char *i_jname, double i_percentage)
 set the parcentage to the default servo torque gain More...
 
void startForceSensorCalibration ()
 start force sensor calibration and wait until finish More...
 
void startInertiaSensorCalibration ()
 start inertia sensor calibration and wait until finish More...
 
void writeAccelerationCommands (const double *i_commands)
 write array of reference accelerations of joint servo More...
 
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 More...
 
void writeTorqueCommands (const double *i_commands)
 write array of reference torques of joint servo More...
 
void writeVelocityCommands (const double *i_commands)
 write array of reference velocities of joint servo More...
 
 ~robot ()
 destructor More...
 
 ~robot ()
 destructor More...
 
- Public Member Functions inherited from hrp::Body
void addSensor (Sensor *sensor, int sensorType, int id)
 
 Body ()
 
 Body (const Body &org)
 
void calcAngularMomentumJacobian (Link *base, dmatrix &H)
 
Vector3 calcCM ()
 
void calcCMJacobian (Link *base, dmatrix &J)
 
void calcForwardKinematics (bool calcVelocity=false, bool calcAcceleration=false)
 
void calcInverseDynamics (Link *link, Vector3 &out_f, Vector3 &out_tau)
 
void calcMassMatrix (dmatrix &out_M)
 
double calcTotalMass ()
 
void calcTotalMomentum (Vector3 &out_P, Vector3 &out_L)
 
void calcTotalMomentumFromJacobian (Vector3 &out_P, Vector3 &out_L)
 
void clearExternalForces ()
 
void clearSensorValues ()
 
LightcreateLight (Link *link, int lightType, const std::string &name)
 
SensorcreateSensor (Link *link, int sensorType, int id, const std::string &name)
 
void getDefaultRootPosition (Vector3 &out_p, Matrix33 &out_R)
 
JointPathPtr getJointPath (Link *baseLink, Link *targetLink)
 
void initializeConfiguration ()
 
bool installCustomizer ()
 
bool installCustomizer (BodyCustomizerInterface *customizerInterface)
 
bool isStaticModel ()
 
Linkjoint (int id) const
 
const std::vector< Link *> & joints () const
 
Lightlight (const std::string &name)
 
Linklink (int index) const
 
Linklink (const std::string &name) const
 
const LinkTraverselinks () const
 
const LinkTraverselinkTraverse () const
 
const std::string & modelName ()
 
const std::string & name ()
 
unsigned int numJoints () const
 
unsigned int numLinks () const
 
unsigned int numSensors (int sensorType) const
 
unsigned int numSensorTypes () const
 
void putInformation (std::ostream &out)
 
LinkrootLink () const
 
Sensorsensor (int sensorType, int sensorId) const
 
TSensor * sensor (const std::string &name) const
 
TSensor * sensor (int id) const
 
void setColumnOfMassMatrix (dmatrix &M, int column)
 
void setDefaultRootPosition (const Vector3 &p, const Matrix33 &R)
 
void setModelName (const std::string &name)
 
void setName (const std::string &name)
 
void setRootLink (Link *link)
 
void setVirtualJointForces ()
 
double totalMass () const
 
void updateLinkColdetModelPositions ()
 
void updateLinkTree ()
 
virtual ~Body ()
 
- Public Member Functions inherited from hrp::Referenced
 Referenced ()
 
virtual ~Referenced ()
 

Public Attributes

double m_accLimit
 
double m_fzLimitRatio
 
double m_maxZmpError
 
std::vector< double > m_servoErrorLimit
 
double m_servoOnDelay
 
- Public Attributes inherited from hrp::Body
 EJ_XY
 
 EJ_XYZ
 
 EJ_Z
 
std::vector< ExtraJointextraJoints
 

Private Member Functions

void calibrateForceSensorOneStep ()
 calibrate force sensor for one sampling period More...
 
void calibrateInertiaSensorOneStep ()
 calibrate inertia sensor for one sampling period More...
 
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 More...
 
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
 

Additional Inherited Members

- Static Public Member Functions inherited from hrp::Body
static BodyInterfacebodyInterface ()
 
- Protected Member Functions inherited from hrp::Referenced
int refCounter ()
 

Detailed Description

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

Member Enumeration Documentation

◆ emg_reason

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() [1/2]

robot::robot ( double  dt)

constructor

Parameters
dtsampling time

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

◆ ~robot() [1/2]

robot::~robot ( )

destructor

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

◆ robot() [2/2]

robot::robot ( )

constructor

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

◆ ~robot() [2/2]

robot::~robot ( )

destructor

Member Function Documentation

◆ addJointGroup()

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

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

◆ calibrateForceSensorOneStep()

void robot::calibrateForceSensorOneStep ( )
private

calibrate force sensor for one sampling period

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

◆ calibrateInertiaSensorOneStep()

void robot::calibrateInertiaSensorOneStep ( )
private

calibrate inertia sensor for one sampling period

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

◆ checkEmergency()

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 665 of file RobotHardware/robot.cpp.

◆ checkJointCommands()

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 630 of file RobotHardware/robot.cpp.

◆ disableDisturbanceObserver()

void robot::disableDisturbanceObserver ( )

disable disturbance observer

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

◆ enableDisturbanceObserver()

void robot::enableDisturbanceObserver ( )

enable disturbance observer

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

◆ gain_control() [1/2]

void robot::gain_control ( )
private

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

◆ gain_control() [2/2]

void robot::gain_control ( int  id)
private

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

◆ init() [1/2]

bool robot::init ( )

◆ init() [2/2]

bool robot::init ( )

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

◆ initializeJointAngle()

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.

◆ isBusy()

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 496 of file RobotHardware/robot.cpp.

◆ lengthDigitalInput()

int robot::lengthDigitalInput ( )

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

◆ lengthDigitalOutput()

int robot::lengthDigitalOutput ( )

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

◆ lengthOfExtraServoState()

size_t robot::lengthOfExtraServoState ( int  id)

get length of extra servo states

Parameters
idjoint id
Returns
length of extra servo states

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

◆ loadGain()

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.

◆ names2ids()

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

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

◆ numBatteries()

int robot::numBatteries ( )

get the number of batteries

Returns
the number of batteries

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

◆ numThermometers()

int robot::numThermometers ( )

get the number of thermometers

Returns
the number of thermometers

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

◆ oneStep()

void robot::oneStep ( )

all processings for one sampling period

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

◆ power() [1/2]

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 437 of file RobotHardware/robot.cpp.

◆ power() [2/2]

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.

◆ readAccelerometer()

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 535 of file RobotHardware/robot.cpp.

◆ readBatteryState()

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 957 of file RobotHardware/robot.cpp.

◆ readCalibState()

int robot::readCalibState ( int  i)

read calibration status of a joint servo

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

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

◆ readDigitalInput()

bool robot::readDigitalInput ( char *  o_din)

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

◆ readDigitalOutput()

bool robot::readDigitalOutput ( char *  o_dout)

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

◆ readDriverTemperature()

int robot::readDriverTemperature ( int  i)

read temperature of motor driver

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

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

◆ readExtraServoState()

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 914 of file RobotHardware/robot.cpp.

◆ readForceSensor()

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 540 of file RobotHardware/robot.cpp.

◆ readGyroSensor()

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 530 of file RobotHardware/robot.cpp.

◆ readJointAngles()

void robot::readJointAngles ( double *  o_angles)

read array of all joint angles[rad]

Parameters
o_anglesarray of all joint angles

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

◆ readJointCommands()

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 558 of file RobotHardware/robot.cpp.

◆ readJointCommandTorques()

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 525 of file RobotHardware/robot.cpp.

◆ readJointTorques()

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 520 of file RobotHardware/robot.cpp.

◆ readJointVelocities()

void robot::readJointVelocities ( double *  o_velocities)

read array of all joint velocities[rad/s]

Parameters
o_anglesarray of all joint velocities

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

◆ readPDControllerTorques()

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 1014 of file RobotHardware/robot.cpp.

◆ readPowerState()

int robot::readPowerState ( int  i)

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 592 of file RobotHardware/robot.cpp.

◆ readPowerStatus()

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 580 of file RobotHardware/robot.cpp.

◆ readServoAlarm()

int robot::readServoAlarm ( int  i)

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 606 of file RobotHardware/robot.cpp.

◆ readServoState()

int robot::readServoState ( int  i)

read servo status of a joint servo

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

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

◆ readThermometer()

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

read thermometer

Parameters
i_rankrank of thermometer
o_temptemperature

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

◆ removeForceSensorOffset()

void robot::removeForceSensorOffset ( )

remove offsets on force sensor outputs

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

◆ servo() [1/2]

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.

◆ servo() [2/2]

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.

◆ setDisturbanceObserverGain()

void robot::setDisturbanceObserverGain ( double  gain)

set disturbance observer gain

Parameters
gaindisturbance observer gain

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

◆ setJointControlMode()

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 1044 of file RobotHardware/robot.cpp.

◆ setJointInertia()

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 994 of file RobotHardware/robot.cpp.

◆ setJointInertias()

void robot::setJointInertias ( const double *  i_mn)

set joint inertias

Parameters
i_mnsarray of joint inertia

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

◆ setProperty()

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

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

◆ setServoErrorLimit() [1/2]

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

◆ setServoErrorLimit() [2/2]

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 842 of file RobotHardware/robot.cpp.

◆ setServoGainPercentage()

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 740 of file RobotHardware/robot.cpp.

◆ setServoTorqueGainPercentage()

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 791 of file RobotHardware/robot.cpp.

◆ startForceSensorCalibration()

void robot::startForceSensorCalibration ( )

start force sensor calibration and wait until finish

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

◆ startInertiaSensorCalibration()

void robot::startInertiaSensorCalibration ( )

start inertia sensor calibration and wait until finish

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

◆ writeAccelerationCommands()

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 573 of file RobotHardware/robot.cpp.

◆ writeDigitalOutput()

bool robot::writeDigitalOutput ( const char *  i_dout)

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

◆ writeDigitalOutputWithMask()

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

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

◆ writeJointCommands()

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 545 of file RobotHardware/robot.cpp.

◆ writeTorqueCommands()

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 563 of file RobotHardware/robot.cpp.

◆ writeVelocityCommands()

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 568 of file RobotHardware/robot.cpp.

Member Data Documentation

◆ accel_sum

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

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

◆ att_sum

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

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

◆ default_dgain

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

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

◆ default_pgain

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

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

◆ default_tqdgain

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

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

◆ default_tqpgain

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

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

◆ dgain

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

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

◆ force_calib_counter

int robot::force_calib_counter
private

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

◆ force_sum

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

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

◆ G

hrp::Vector3 robot::G
private

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

◆ gain_counter

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

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

◆ gyro_sum

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

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

◆ inertia_calib_counter

int robot::inertia_calib_counter
private

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

◆ m_accLimit

double robot::m_accLimit

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

◆ m_calibJointName

std::string robot::m_calibJointName
private

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

◆ m_calibOptions

std::string robot::m_calibOptions
private

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

◆ m_calibRequested

bool robot::m_calibRequested
private

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

◆ m_commandOld

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

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

◆ m_dt

double robot::m_dt
private

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

◆ m_enable_poweroff_check

bool robot::m_enable_poweroff_check
private

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

◆ m_fzLimitRatio

double robot::m_fzLimitRatio

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

◆ m_jointGroups

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

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

◆ m_lLegForceSensorId

int robot::m_lLegForceSensorId
private

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

◆ m_maxZmpError

double robot::m_maxZmpError

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

◆ m_pdgainsFilename

std::string robot::m_pdgainsFilename
private

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

◆ m_reportedEmergency

bool robot::m_reportedEmergency
private

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

◆ m_rLegForceSensorId

int robot::m_rLegForceSensorId
private

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

◆ m_servoErrorLimit

std::vector< double > robot::m_servoErrorLimit

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

◆ m_servoOnDelay

double robot::m_servoOnDelay

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

◆ m_velocityOld

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

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

◆ old_dgain

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

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

◆ old_pgain

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

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

◆ old_tqdgain

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

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

◆ old_tqpgain

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

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

◆ pgain

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

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

◆ tqdgain

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

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

◆ tqpgain

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

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

◆ wait_sem

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 Sat Dec 17 2022 03:52:22