4 #include <boost/array.hpp> 7 #include "hrpsys/io/iob.h" 36 bool servo(
int jid,
bool turnon);
43 bool servo(
const char *jname,
bool turnon);
50 bool power(
int jid,
bool turnon);
57 bool power(
const char *jname,
bool turnon);
144 double &o_current,
double &o_soc);
326 bool addJointGroup(
const char *gname,
const std::vector<std::string>& jnames);
376 bool names2ids(
const std::vector<std::string> &i_names,
377 std::vector<int> &o_ids);
387 std::vector< boost::array<double,3> >
att_sum;
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
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)
std::vector< double > gain_counter
void startForceSensorCalibration()
start force sensor calibration and wait until finish
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
std::vector< double > default_pgain
void setJointInertias(const double *i_mn)
set joint inertias
int readDriverTemperature(int i)
read temperature of motor driver
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
emg_reason
reasons of emergency
void startInertiaSensorCalibration()
start inertia sensor calibration and wait until finish
void readAccelerometer(unsigned int i_rank, double *o_accs)
read accelerometer output
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
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)
void readGyroSensor(unsigned int i_rank, double *o_rates)
read gyro sensor output
std::vector< double > tqpgain
std::vector< double > m_servoErrorLimit
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
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
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
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