00001
00010 #include <rtm/CorbaNaming.h>
00011 #include "hrpsys/util/VectorConvert.h"
00012 #include "RobotHardware.h"
00013 #include "robot.h"
00014
00015 #include <hrpModel/Sensor.h>
00016 #include <hrpModel/ModelLoaderUtil.h>
00017
00018 using namespace OpenHRP;
00019 using namespace hrp;
00020
00021
00022
00023 static const char* robothardware_spec[] =
00024 {
00025 "implementation_id", "RobotHardware",
00026 "type_name", "RobotHardware",
00027 "description", "RobotHardware",
00028 "version", HRPSYS_PACKAGE_VERSION,
00029 "vendor", "AIST",
00030 "category", "example",
00031 "activity_type", "DataFlowComponent",
00032 "max_instance", "1",
00033 "language", "C++",
00034 "lang_type", "compile",
00035
00036 "conf.default.isDemoMode", "0",
00037 "conf.default.fzLimitRatio", "2.0",
00038 "conf.default.servoErrorLimit", ",",
00039 "conf.default.jointAccelerationLimit", "0",
00040
00041 ""
00042 };
00043
00044
00045 RobotHardware::RobotHardware(RTC::Manager* manager)
00046 : RTC::DataFlowComponentBase(manager),
00047
00048 m_isDemoMode(0),
00049 m_qRefIn("qRef", m_qRef),
00050 m_dqRefIn("dqRef", m_dqRef),
00051 m_tauRefIn("tauRef", m_tauRef),
00052 m_qOut("q", m_q),
00053 m_dqOut("dq", m_dq),
00054 m_tauOut("tau", m_tau),
00055 m_ctauOut("ctau", m_ctau),
00056 m_servoStateOut("servoState", m_servoState),
00057 m_emergencySignalOut("emergencySignal", m_emergencySignal),
00058 m_rstate2Out("rstate2", m_rstate2),
00059 m_RobotHardwareServicePort("RobotHardwareService"),
00060
00061 dummy(0)
00062 {
00063 }
00064
00065 RobotHardware::~RobotHardware()
00066 {
00067 }
00068
00069
00070 RTC::ReturnCode_t RobotHardware::onInitialize()
00071 {
00072
00073
00074
00075 addInPort("qRef", m_qRefIn);
00076 addInPort("dqRef", m_dqRefIn);
00077 addInPort("tauRef", m_tauRefIn);
00078
00079 addOutPort("q", m_qOut);
00080 addOutPort("dq", m_dqOut);
00081 addOutPort("tau", m_tauOut);
00082 addOutPort("ctau", m_ctauOut);
00083 addOutPort("servoState", m_servoStateOut);
00084 addOutPort("emergencySignal", m_emergencySignalOut);
00085 addOutPort("rstate2", m_rstate2Out);
00086
00087
00088 m_RobotHardwareServicePort.registerProvider("service0", "RobotHardwareService", m_service0);
00089
00090
00091
00092
00093 addPort(m_RobotHardwareServicePort);
00094
00095
00096
00097 RTC::Properties& prop = getProperties();
00098 double dt = 0.0;
00099 coil::stringTo(dt, prop["dt"].c_str());
00100 if (!dt) {
00101 std::cerr << m_profile.instance_name << ": joint command velocity check is disabled" << std::endl;
00102 }
00103 m_robot = boost::shared_ptr<robot>(new robot(dt));
00104
00105
00106 RTC::Manager& rtcManager = RTC::Manager::instance();
00107 std::string nameServer = rtcManager.getConfig()["corba.nameservers"];
00108 int comPos = nameServer.find(",");
00109 if (comPos < 0){
00110 comPos = nameServer.length();
00111 }
00112 nameServer = nameServer.substr(0, comPos);
00113 RTC::CorbaNaming naming(rtcManager.getORB(), nameServer.c_str());
00114 if (!loadBodyFromModelLoader(m_robot, prop["model"].c_str(),
00115 CosNaming::NamingContext::_duplicate(naming.getRootContext())
00116 )){
00117 if (prop["model"] == ""){
00118 std::cerr << "[" << m_profile.instance_name << "] path to the model file is not defined. Please check the configuration file" << std::endl;
00119 }else{
00120 std::cerr << "[" << m_profile.instance_name << "] failed to load model[" << prop["model"] << "]" << std::endl;
00121 }
00122 }
00123
00124 std::vector<std::string> keys = prop.propertyNames();
00125 for (unsigned int i=0; i<keys.size(); i++){
00126 m_robot->setProperty(keys[i].c_str(), prop[keys[i]].c_str());
00127 }
00128 std::cout << "dof = " << m_robot->numJoints() << std::endl;
00129 if (!m_robot->init()) return RTC::RTC_ERROR;
00130
00131 m_service0.setRobot(m_robot);
00132
00133 m_q.data.length(m_robot->numJoints());
00134 m_dq.data.length(m_robot->numJoints());
00135 m_tau.data.length(m_robot->numJoints());
00136 m_ctau.data.length(m_robot->numJoints());
00137 m_servoState.data.length(m_robot->numJoints());
00138 m_qRef.data.length(m_robot->numJoints());
00139 m_dqRef.data.length(m_robot->numJoints());
00140 m_tauRef.data.length(m_robot->numJoints());
00141
00142 int ngyro = m_robot->numSensors(Sensor::RATE_GYRO);
00143 std::cout << "the number of gyros = " << ngyro << std::endl;
00144 m_rate.resize(ngyro);
00145 m_rateOut.resize(ngyro);
00146 for (unsigned int i=0; i<m_rate.size(); i++){
00147 Sensor *s = m_robot->sensor(Sensor::RATE_GYRO, i);
00148 std::cout << s->name << std::endl;
00149 m_rateOut[i] = new OutPort<TimedAngularVelocity3D>(s->name.c_str(), m_rate[i]);
00150 registerOutPort(s->name.c_str(), *m_rateOut[i]);
00151 }
00152
00153 int nacc = m_robot->numSensors(Sensor::ACCELERATION);
00154 std::cout << "the number of accelerometers = " << nacc << std::endl;
00155 m_acc.resize(nacc);
00156 m_accOut.resize(nacc);
00157 for (unsigned int i=0; i<m_acc.size(); i++){
00158 Sensor *s = m_robot->sensor(Sensor::ACCELERATION, i);
00159 std::cout << s->name << std::endl;
00160 m_accOut[i] = new OutPort<TimedAcceleration3D>(s->name.c_str(), m_acc[i]);
00161 registerOutPort(s->name.c_str(), *m_accOut[i]);
00162 }
00163
00164 int nforce = m_robot->numSensors(Sensor::FORCE);
00165 std::cout << "the number of force sensors = " << nforce << std::endl;
00166 m_force.resize(nforce);
00167 m_forceOut.resize(nforce);
00168 for (unsigned int i=0; i<m_force.size(); i++){
00169 Sensor *s = m_robot->sensor(Sensor::FORCE, i);
00170 std::cout << s->name << std::endl;
00171 m_forceOut[i] = new OutPort<TimedDoubleSeq>(s->name.c_str(), m_force[i]);
00172 m_force[i].data.length(6);
00173 registerOutPort(s->name.c_str(), *m_forceOut[i]);
00174 }
00175
00176
00177
00178 bindParameter("isDemoMode", m_isDemoMode, "0");
00179 bindParameter("servoErrorLimit", m_robot->m_servoErrorLimit, ",");
00180 bindParameter("fzLimitRatio", m_robot->m_fzLimitRatio, "2");
00181 bindParameter("jointAccelerationLimit", m_robot->m_accLimit, "0");
00182
00183
00184
00185 return RTC::RTC_OK;
00186 }
00187
00188
00189
00190
00191
00192
00193
00194
00195
00196
00197
00198
00199
00200
00201
00202
00203
00204
00205
00206
00207
00208
00209
00210
00211
00212
00213
00214
00215
00216
00217
00218
00219
00220
00221
00222
00223
00224 RTC::ReturnCode_t RobotHardware::onExecute(RTC::UniqueId ec_id)
00225 {
00226
00227 Time tm;
00228 this->getTimeNow(tm);
00229
00230 if (!m_isDemoMode){
00231 robot::emg_reason reason;
00232 int id;
00233 if (m_robot->checkEmergency(reason, id)){
00234 if (reason == robot::EMG_SERVO_ERROR || reason == robot::EMG_POWER_OFF){
00235 m_robot->servo("all", false);
00236 m_emergencySignal.data = reason;
00237 m_emergencySignalOut.write();
00238 } else if (reason == robot::EMG_SERVO_ALARM) {
00239 m_emergencySignal.data = reason;
00240 m_emergencySignalOut.write();
00241 }
00242 }
00243 }
00244
00245 if (m_qRefIn.isNew()){
00246 m_qRefIn.read();
00247
00248 if (!m_isDemoMode
00249 && m_robot->checkJointCommands(m_qRef.data.get_buffer())){
00250 m_robot->servo("all", false);
00251 m_emergencySignal.data = robot::EMG_SERVO_ERROR;
00252 m_emergencySignalOut.write();
00253 }else{
00254
00255 m_robot->writeJointCommands(m_qRef.data.get_buffer());
00256 }
00257 }
00258 if (m_dqRefIn.isNew()){
00259 m_dqRefIn.read();
00260
00261
00262 m_robot->writeVelocityCommands(m_dqRef.data.get_buffer());
00263 }
00264 if (m_tauRefIn.isNew()){
00265 m_tauRefIn.read();
00266
00267
00268 m_robot->writeTorqueCommands(m_tauRef.data.get_buffer());
00269 }
00270
00271
00272 m_robot->readJointAngles(m_q.data.get_buffer());
00273 m_q.tm = tm;
00274 m_robot->readJointVelocities(m_dq.data.get_buffer());
00275 m_dq.tm = tm;
00276 m_robot->readJointTorques(m_tau.data.get_buffer());
00277 m_tau.tm = tm;
00278 m_robot->readJointCommandTorques(m_ctau.data.get_buffer());
00279 m_ctau.tm = tm;
00280 for (unsigned int i=0; i<m_rate.size(); i++){
00281 double rate[3];
00282 m_robot->readGyroSensor(i, rate);
00283 m_rate[i].data.avx = rate[0];
00284 m_rate[i].data.avy = rate[1];
00285 m_rate[i].data.avz = rate[2];
00286 m_rate[i].tm = tm;
00287 }
00288
00289 for (unsigned int i=0; i<m_acc.size(); i++){
00290 double acc[3];
00291 m_robot->readAccelerometer(i, acc);
00292 m_acc[i].data.ax = acc[0];
00293 m_acc[i].data.ay = acc[1];
00294 m_acc[i].data.az = acc[2];
00295 m_acc[i].tm = tm;
00296 }
00297
00298 for (unsigned int i=0; i<m_force.size(); i++){
00299 m_robot->readForceSensor(i, m_force[i].data.get_buffer());
00300 m_force[i].tm = tm;
00301 }
00302
00303 for (unsigned int i=0; i<m_servoState.data.length(); i++){
00304 size_t len = m_robot->lengthOfExtraServoState(i)+1;
00305 m_servoState.data[i].length(len);
00306 int status = 0, v;
00307 v = m_robot->readCalibState(i);
00308 status |= v<< OpenHRP::RobotHardwareService::CALIB_STATE_SHIFT;
00309 v = m_robot->readPowerState(i);
00310 status |= v<< OpenHRP::RobotHardwareService::POWER_STATE_SHIFT;
00311 v = m_robot->readServoState(i);
00312 status |= v<< OpenHRP::RobotHardwareService::SERVO_STATE_SHIFT;
00313 v = m_robot->readServoAlarm(i);
00314 status |= v<< OpenHRP::RobotHardwareService::SERVO_ALARM_SHIFT;
00315 v = m_robot->readDriverTemperature(i);
00316 status |= v<< OpenHRP::RobotHardwareService::DRIVER_TEMP_SHIFT;
00317 m_servoState.data[i][0] = status;
00318 m_robot->readExtraServoState(i, (int *)(m_servoState.data[i].get_buffer()+1));
00319 }
00320 m_servoState.tm = tm;
00321
00322 getStatus2(m_rstate2.data);
00323 m_rstate2.tm = tm;
00324
00325 m_robot->oneStep();
00326
00327 m_qOut.write();
00328 m_dqOut.write();
00329 m_tauOut.write();
00330 m_ctauOut.write();
00331 m_servoStateOut.write();
00332 for (unsigned int i=0; i<m_rateOut.size(); i++){
00333 m_rateOut[i]->write();
00334 }
00335 for (unsigned int i=0; i<m_accOut.size(); i++){
00336 m_accOut[i]->write();
00337 }
00338 for (unsigned int i=0; i<m_forceOut.size(); i++){
00339 m_forceOut[i]->write();
00340 }
00341 m_rstate2Out.write();
00342
00343 return RTC::RTC_OK;
00344 }
00345
00346 template<class T>
00347 void getStatus(boost::shared_ptr<robot> robot, T& rstate)
00348 {
00349 rstate.angle.length(robot->numJoints());
00350 robot->readJointAngles(rstate.angle.get_buffer());
00351
00352 rstate.command.length(robot->numJoints());
00353 robot->readJointCommands(rstate.command.get_buffer());
00354
00355 rstate.torque.length(robot->numJoints());
00356 if (!robot->readJointTorques(rstate.torque.get_buffer())){
00357 for (unsigned int i=0; i<rstate.torque.length(); i++){
00358 rstate.torque[i] = 0.0;
00359 }
00360 }
00361
00362 rstate.servoState.length(robot->numJoints());
00363 int v, status;
00364 for(unsigned int i=0; i < rstate.servoState.length(); ++i){
00365 size_t len = robot->lengthOfExtraServoState(i)+1;
00366 rstate.servoState[i].length(len);
00367 status = 0;
00368 v = robot->readCalibState(i);
00369 status |= v<< OpenHRP::RobotHardwareService::CALIB_STATE_SHIFT;
00370 v = robot->readPowerState(i);
00371 status |= v<< OpenHRP::RobotHardwareService::POWER_STATE_SHIFT;
00372 v = robot->readServoState(i);
00373 status |= v<< OpenHRP::RobotHardwareService::SERVO_STATE_SHIFT;
00374 v = robot->readServoAlarm(i);
00375 status |= v<< OpenHRP::RobotHardwareService::SERVO_ALARM_SHIFT;
00376 v = robot->readDriverTemperature(i);
00377 status |= v<< OpenHRP::RobotHardwareService::DRIVER_TEMP_SHIFT;
00378 rstate.servoState[i][0] = status;
00379 robot->readExtraServoState(i, (int *)(rstate.servoState[i].get_buffer()+1));
00380 }
00381
00382 rstate.rateGyro.length(robot->numSensors(Sensor::RATE_GYRO));
00383 for (unsigned int i=0; i<rstate.rateGyro.length(); i++){
00384 rstate.rateGyro[i].length(3);
00385 robot->readGyroSensor(i, rstate.rateGyro[i].get_buffer());
00386 }
00387
00388 rstate.accel.length(robot->numSensors(Sensor::ACCELERATION));
00389 for (unsigned int i=0; i<rstate.accel.length(); i++){
00390 rstate.accel[i].length(3);
00391 robot->readAccelerometer(i, rstate.accel[i].get_buffer());
00392 }
00393
00394 rstate.force.length(robot->numSensors(Sensor::FORCE));
00395 for (unsigned int i=0; i<rstate.force.length(); i++){
00396 rstate.force[i].length(6);
00397 robot->readForceSensor(i, rstate.force[i].get_buffer());
00398 }
00399
00400 robot->readPowerStatus(rstate.voltage, rstate.current);
00401 }
00402
00403 void RobotHardware::getStatus2(OpenHRP::RobotHardwareService::RobotState2 &rstate2)
00404 {
00405 getStatus(m_robot, rstate2);
00406 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2
00407 rstate2.batteries.length(m_robot->numBatteries());
00408 for(unsigned int i=0; i<rstate2.batteries.length(); i++){
00409 m_robot->readBatteryState(i,
00410 rstate2.batteries[i].voltage,
00411 rstate2.batteries[i].current,
00412 rstate2.batteries[i].soc);
00413 }
00414 rstate2.temperature.length(m_robot->numThermometers());
00415 for (unsigned int i=0; i<rstate2.temperature.length(); i++){
00416 m_robot->readThermometer(i, rstate2.temperature[i]);
00417 }
00418 #endif
00419 }
00420
00421
00422
00423
00424
00425
00426
00427
00428
00429
00430
00431
00432
00433
00434
00435
00436
00437
00438
00439
00440
00441
00442
00443
00444
00445
00446
00447
00448
00449
00450
00451
00452
00453
00454
00455
00456
00457
00458 extern "C"
00459 {
00460
00461 void RobotHardwareInit(RTC::Manager* manager)
00462 {
00463 RTC::Properties profile(robothardware_spec);
00464 manager->registerFactory(profile,
00465 RTC::Create<RobotHardware>,
00466 RTC::Delete<RobotHardware>);
00467 }
00468
00469 };
00470
00471