BodyRTC.cpp
Go to the documentation of this file.
00001 #include <iostream>
00002 #include <hrpModel/Sensor.h>
00003 #include <hrpModel/Link.h>
00004 #include "BodyRTC.h"
00005 #include "PortHandler.h"
00006 
00007 using namespace hrp;
00008 using namespace RTC;
00009 
00010 // Module specification
00011 // <rtc-template block="module_spec">
00012 const char* BodyRTC::bodyrtc_spec[] =
00013 {
00014     "implementation_id", "BodyRTC",
00015     "type_name",         "BodyRTC",
00016     "description",       "BodyRTC component",
00017     "version",           "0.1",
00018     "vendor",            "AIST",
00019     "category",          "Generic",
00020     "activity_type",     "DataFlowComponent",
00021     "max_instance",      "10",
00022     "language",          "C++",
00023     "lang_type",         "compile",
00024     // Configuration variables
00025 
00026     ""
00027 };
00028 
00029 BodyRTC::BodyRTC(RTC::Manager* manager)
00030     : Body(),
00031       DataFlowComponentBase(manager),
00032       m_RobotHardwareServicePort("RobotHardwareService"),
00033       m_resetPosition(true),
00034       dummy(0)
00035 {
00036     //std::cout << "constructor of BodyRTC"  << std::endl;
00037 }
00038 
00039 BodyRTC::~BodyRTC(void)
00040 {
00041     //std::cout << "destructor of BodyRTC"  << std::endl;
00042     for (size_t i=0; i<m_inports.size(); i++){
00043         delete m_inports[i];
00044     }
00045     for (size_t i=0; i<m_outports.size(); i++){
00046         delete m_outports[i];
00047     }
00048 }
00049 
00050 void BodyRTC::writeDataPorts(double time)
00051 {
00052     for (size_t i=0; i<m_outports.size(); i++){
00053         m_outports[i]->update(time);
00054     }
00055 }
00056 
00057 void BodyRTC::readDataPorts()
00058 {
00059     for (size_t i=0; i<m_inports.size(); i++){
00060         m_inports[i]->update();
00061     }
00062 }
00063 
00064 #define DEFAULT_ANGLE_ERROR_LIMIT 0.2 // [rad] // copied from robot.cpp
00065 RTC::ReturnCode_t BodyRTC::setup(){
00066     std::cout << "BodyRTC::setup(), numJoints = " << numJoints() << std::endl;
00067     angles.resize(numJoints());
00068     commands.resize(numJoints());
00069     accels.resize(numSensors(hrp::Sensor::ACCELERATION));
00070     gyros.resize(numSensors(hrp::Sensor::RATE_GYRO));
00071     forces.resize(numSensors(hrp::Sensor::FORCE));
00072     calib_status.resize(numJoints());
00073     servo_status.resize(numJoints());
00074     power_status.resize(numJoints());
00075     m_servoErrorLimit.resize(numJoints());
00076     for(unsigned int i = 0; i < numJoints(); i++) {
00077         calib_status[i] = servo_status[i] = power_status[i] = OpenHRP::RobotHardwareService::SWITCH_ON;
00078         m_servoErrorLimit[i] = DEFAULT_ANGLE_ERROR_LIMIT;
00079     }
00080     m_emergencyReason = EMG_NONE; // clear
00081     m_emergencyId = -1;
00082 }
00083 
00084 void parsePortConfig(const std::string &config, 
00085                      std::string &name, std::string &type,
00086                      std::vector<std::string> &elements)
00087 {
00088     std::string::size_type colon = 0, start=0; 
00089     colon = config.find(':', start);
00090     if (colon == std::string::npos){
00091         std::cerr << "can't find the first separator in [" << config << "]" 
00092                   << std::endl;
00093         return;
00094     }
00095     name = config.substr(start, colon);
00096     start = colon+1;
00097     colon = config.find(':', start);
00098     if (colon == std::string::npos){
00099         type = config.substr(start);
00100         return;
00101     }
00102     std::string elist = config.substr(start, colon-start);
00103     std::string::size_type comma;
00104     start = 0;
00105     comma = elist.find(',', start);
00106     while (comma != std::string::npos){
00107         std::string e = elist.substr(start, comma-start);
00108         elements.push_back(e);
00109         start = comma+1;
00110         comma = elist.find(',', start);
00111     }
00112     elements.push_back(elist.substr(start));
00113     start = colon+1;
00114     type = config.substr(start);
00115 }
00116 
00117 bool getJointList(hrp::Body *body, const std::vector<std::string> &elements,
00118                   std::vector<hrp::Link *> &joints)
00119 {
00120     if (elements.size() == 0){
00121         for (unsigned int i=0; i<body->numJoints(); i++){
00122             joints.push_back(body->joint(i));
00123         }
00124     }else{
00125         for (size_t i=0; i<elements.size(); i++){
00126             hrp::Link *j = body->link(elements[i]);
00127             if (j){
00128                 joints.push_back(j);
00129             }else{
00130                 std::cerr << "can't find a joint(" << elements[i] << ")"
00131                           << std::endl;
00132                 return false;
00133             }
00134         }
00135     }
00136     return true;
00137 }
00138 
00139 void BodyRTC::createInPort(const std::string &config)
00140 {
00141     std::string name, type;
00142     std::vector<std::string> elements;
00143     parsePortConfig(config, name, type, elements);
00144     if (type == "JOINT_VALUE"){
00145         std::vector<hrp::Link *> joints;
00146         if (getJointList(this, elements, joints)){
00147             m_inports.push_back(
00148                 new JointValueInPortHandler(this, name.c_str(), joints, &servo_status));
00149         }
00150     }else if(type == "JOINT_VELOCITY"){
00151         std::vector<hrp::Link *> joints;
00152         if (getJointList(this, elements, joints)){
00153             m_inports.push_back(
00154                 new JointVelocityInPortHandler(this, name.c_str(), joints, &servo_status));
00155         }
00156     }else if(type == "JOINT_ACCELERATION"){
00157         std::vector<hrp::Link *> joints;
00158         if (getJointList(this, elements, joints)){
00159             m_inports.push_back(
00160                 new JointAccelerationInPortHandler(this, name.c_str(),joints, &servo_status));
00161         }
00162     }else if(type == "JOINT_TORQUE"){
00163         std::vector<hrp::Link *> joints;
00164         if (getJointList(this, elements, joints)){
00165             m_inports.push_back(
00166                 new JointTorqueInPortHandler(this, name.c_str(), joints, &servo_status));
00167         }
00168     }else if(type == "EXTERNAL_FORCE"){
00169         std::cout << "EXTERNAL_FORCE is not implemented yet" << std::endl;
00170     }else if(type == "ABS_TRANSFORM"){
00171         std::vector<hrp::Link *> joints;
00172         if (getJointList(this, elements, joints) && joints.size() == 1){
00173             m_inports.push_back(
00174                 new AbsTransformInPortHandler(this, name.c_str(), joints[0]));
00175         } else if (elements.size() == 1) {
00176             hrp::Link *l=this->link(elements[0]);
00177             if (l){
00178                 m_inports.push_back(
00179                                      new AbsTransformInPortHandler(this, name.c_str(), l));
00180                 return;
00181             }
00182             std::cerr << "can't find a link(or a sensor)(" << elements[0] << ")" 
00183                       << std::endl;
00184         }
00185     }else if(type == "ABS_VELOCITY"){
00186         std::vector<hrp::Link *> joints;
00187         if (getJointList(this, elements, joints) && joints.size() == 1){
00188             m_inports.push_back(
00189                 new AbsVelocityInPortHandler(this, name.c_str(), joints[0]));
00190         }
00191     }else if(type == "ABS_ACCELERATION"){
00192         std::vector<hrp::Link *> joints;
00193         if (getJointList(this, elements, joints) && joints.size() == 1){
00194             m_inports.push_back(
00195                 new AbsAccelerationInPortHandler(this,name.c_str(),joints[0]));
00196         }
00197     }else if(type == "FRAME_RATE"){
00198         VisionSensor *s = this->sensor<VisionSensor>(elements[0]);
00199         if (!s){
00200             std::cerr << "can't find a sensor(" << elements[0] << ")" 
00201                       << std::endl;
00202             return;
00203         }
00204         m_inports.push_back(new FrameRateInPortHandler(this,name.c_str(),s));
00205     }else if(type == "LIGHT_SWITCH"){
00206         Light *l = this->light(elements[0]);
00207         if (!l){
00208             std::cerr << "can't find a light(" << elements[0] << ")" 
00209                       << std::endl;
00210             return;
00211         }
00212         m_inports.push_back(new LightSwitchInPortHandler(this,name.c_str(),l));
00213     }else{
00214         std::cerr << "unknown InPort data type(" << type << ")" << std::endl;
00215     }
00216 }
00217 
00218 void BodyRTC::createOutPort(const std::string &config)
00219 {
00220     std::string name, type;
00221     std::vector<std::string> elements;
00222     parsePortConfig(config, name, type, elements);
00223     if (type == "JOINT_VALUE"){
00224         std::vector<hrp::Link *> joints;
00225         if (getJointList(this, elements, joints)){
00226             m_outports.push_back(
00227                 new JointValueOutPortHandler(this, name.c_str(), joints));
00228         }
00229     }else if(type == "JOINT_VELOCITY"){
00230         std::vector<hrp::Link *> joints;
00231         if (getJointList(this, elements, joints)){
00232             m_outports.push_back(
00233                 new JointVelocityOutPortHandler(this, name.c_str(), joints));
00234         }
00235     }else if(type == "JOINT_ACCELERATION"){
00236         std::vector<hrp::Link *> joints;
00237         if (getJointList(this, elements, joints)){
00238             m_outports.push_back(
00239                 new JointAccelerationOutPortHandler(this,name.c_str(),joints));
00240         }
00241     }else if(type == "JOINT_TORQUE"){
00242         std::vector<hrp::Link *> joints;
00243         if (getJointList(this, elements, joints)){
00244             m_outports.push_back(
00245                 new JointTorqueOutPortHandler(this, name.c_str(), joints));
00246         }
00247     }else if(type == "ABS_TRANSFORM"){
00248         if (elements.size()!=1){
00249             std::cerr << "link name is not specified for port " << name 
00250                       << std::endl;
00251             return;
00252         }
00253         hrp::Link *l=this->link(elements[0]);
00254         if (l){
00255             m_outports.push_back(
00256                 new AbsTransformOutPortHandler(this, name.c_str(), l));
00257             return;
00258         }
00259         hrp::Sensor *s;
00260         s = this->sensor<AccelSensor>(elements[0]);
00261         if (!s) s = this->sensor<RateGyroSensor>(elements[0]);
00262         if (!s) s = this->sensor<ForceSensor>(elements[0]);
00263         if (!s) s = this->sensor<RangeSensor>(elements[0]);
00264         if (!s) s = this->sensor<VisionSensor>(elements[0]);
00265         if (s){
00266             m_outports.push_back(
00267                 new AbsTransformOutPortHandler(this, name.c_str(), s));
00268             return;
00269         }
00270         std::cerr << "can't find a link(or a sensor)(" << elements[0] << ")" 
00271                   << std::endl;
00272     }else if(type == "ABS_VELOCITY"){
00273         if (elements.size()!=1){
00274             std::cerr << "link name is not specified for port " << name
00275                       << std::endl;
00276             return;
00277         }
00278         hrp::Link *l=this->link(elements[0]);
00279         if (l){
00280             m_outports.push_back(
00281                 new AbsVelocityOutPortHandler(this, name.c_str(), l));
00282         }else{
00283             std::cerr << "can't find a link(" << elements[0] << ")" 
00284                       << std::endl;
00285         }
00286     }else if(type == "ABS_ACCELERATION"){
00287         if (elements.size()!=1){
00288             std::cerr << "link name is not specified for port " << name
00289                       << std::endl;
00290             return;
00291         }
00292         hrp::Link *l=this->link(elements[0]);
00293         if (l){
00294             m_outports.push_back(
00295                 new AbsAccelerationOutPortHandler(this, name.c_str(), l));
00296         }else{
00297             std::cerr << "can't find a link(" << elements[0] << ")" 
00298                       << std::endl;
00299         }
00300     }else if(type == "FORCE_SENSOR"){
00301         if (elements.size()!=1){
00302             std::cerr << "sensor name is not specified for port" << name 
00303                       << std::endl;
00304             return;
00305         }
00306         ForceSensor *s = this->sensor<ForceSensor>(elements[0]);
00307         if (!s){
00308             std::cerr << "can't find a sensor(" << elements[0] << ")" 
00309                       << std::endl;
00310             return;
00311         }
00312         m_outports.push_back(new ForceSensorPortHandler(this, name.c_str(),s));
00313                                                         
00314     }else if(type == "RATE_GYRO_SENSOR"){
00315         if (elements.size()!=1){
00316             std::cerr << "sensor name is not specified for port " << name
00317                       << std::endl;
00318             return;
00319         }
00320         RateGyroSensor *s = this->sensor<RateGyroSensor>(elements[0]);
00321         if (!s){
00322             std::cerr << "can't find a sensor(" << elements[0] << ")" 
00323                       << std::endl;
00324             return;
00325         }
00326         m_outports.push_back(new RateGyroSensorPortHandler(this, name.c_str(),
00327                                                            s));
00328     }else if(type == "ACCELERATION_SENSOR"){
00329         if (elements.size()!=1){
00330             std::cerr << "sensor name is not specified for port " << name
00331                       << std::endl;
00332             return;
00333         }
00334         AccelSensor *s = this->sensor<AccelSensor>(elements[0]);
00335         if (!s){
00336             std::cerr << "can't find a sensor(" << elements[0] << ")" 
00337                       << std::endl;
00338             return;
00339         }
00340         m_outports.push_back(new AccelSensorPortHandler(this, name.c_str(),s));
00341                                                         
00342     }else if(type == "RANGE_SENSOR"){
00343         if (elements.size()!=1){
00344             std::cerr << "sensor name is not specified for port " << name 
00345                       << std::endl;
00346             return;
00347         }
00348         RangeSensor *s = this->sensor<RangeSensor>(elements[0]);
00349         if (!s){
00350             std::cerr << "can't find a sensor(" << elements[0] << ")" 
00351                       << std::endl;
00352             return;
00353         }
00354         m_outports.push_back(new RangeSensorPortHandler(this, name.c_str(),s));
00355                                                         
00356     }else if(type == "VISION_SENSOR"){
00357         if (elements.size()!=1){
00358             std::cerr << "sensor name is not specified for port " << name
00359                       << std::endl;
00360             return;
00361         }
00362         VisionSensor *s = this->sensor<VisionSensor>(elements[0]);
00363         if (!s){
00364             std::cerr << "can't find a sensor(" << elements[0] << ")" 
00365                       << std::endl;
00366             return;
00367         }
00368         m_outports.push_back(new VisionSensorPortHandler(this,name.c_str(),s));
00369     }else if(type == "POINT_CLOUD"){
00370         if (elements.size()!=1){
00371             std::cerr << "sensor name is not specified for port " << name
00372                       << std::endl;
00373             return;
00374         }
00375         VisionSensor *s = this->sensor<VisionSensor>(elements[0]);
00376         if (!s){
00377             std::cerr << "can't find a sensor(" << elements[0] << ")" 
00378                       << std::endl;
00379             return;
00380         }
00381         m_outports.push_back(new PointCloudPortHandler(this,name.c_str(),s));
00382     }else if(type == "CONSTRAINT_FORCE"){
00383         std::cout << "CONSTRAINT_FORCE is not implemented yet" << std::endl;
00384     }else{
00385         std::cerr << "unknown OutPort data type(" << type << ")" << std::endl;
00386     }
00387 
00388     m_outports.push_back(new EmergencySignalPortHandler(this, "emergencySignal", this));
00389     m_outports.push_back(new ServoStatePortHandler(this, "servoState", this));
00390 
00391     m_service0.setRobot(this);
00392     m_RobotHardwareServicePort.registerProvider("service0", "RobotHardwareService", m_service0);
00393     addPort(m_RobotHardwareServicePort);
00394 }
00395 
00396 bool BodyRTC::names2ids(const std::vector<std::string> &i_names,
00397                         std::vector<int> &o_ids)
00398 {
00399     bool ret = true;
00400     for (unsigned int i=0; i<i_names.size(); i++){
00401         hrp::Link *l = this->link(i_names[i].c_str());
00402         if (!l){
00403             std::cout << "joint named [" << i_names[i] << "] not found"
00404                       << std::endl;
00405             ret = false;
00406         }else{
00407             o_ids.push_back(l->jointId);
00408         }
00409     }
00410     return ret;
00411 }
00412 
00413 void BodyRTC::getStatus(OpenHRP::RobotHardwareService::RobotState* rs) {
00414     rs->angle.length(numJoints());
00415     rs->command.length(numJoints());
00416     for(size_t i = 0; i < numJoints(); i++) {
00417         rs->angle[i] = angles[i];
00418         rs->command[i] = commands[i];
00419     }
00420     rs->force.length(forces.size());
00421     for(size_t j = 0; j < forces.size(); j++) {
00422         rs->force[j].length(6);
00423         for(size_t i = 0; i < 6; i++ ) rs->force[j][i] = forces[j][i];
00424     }
00425     rs->rateGyro.length(gyros.size());
00426     for(size_t j = 0; j < gyros.size() ; j++) {
00427         rs->rateGyro[j].length(3);
00428         for(size_t i = 0; i < 3; i++ ) rs->rateGyro[j][i] = gyros[j][i];
00429     }
00430     rs->accel.length(accels.size());
00431     for(size_t j = 0; j < accels.size(); j++) {
00432         rs->accel[j].length(3);
00433         for(size_t i = 0; i < 3; i++ ) rs->accel[j][i] = accels[j][i];
00434     }
00435 
00436     rs->servoState.length(numJoints());
00437     int v, status;
00438     for(unsigned int i=0; i < rs->servoState.length(); ++i){
00439         //size_t len = lengthOfExtraServoState(i)+1;
00440         rs->servoState[i].length(1);
00441         status = 0;
00442         v = readCalibState(i);
00443         status |= v<< OpenHRP::RobotHardwareService::CALIB_STATE_SHIFT;
00444         v = readPowerState(i);
00445         status |= v<< OpenHRP::RobotHardwareService::POWER_STATE_SHIFT;
00446         v = readServoState(i);
00447         status |= v<< OpenHRP::RobotHardwareService::SERVO_STATE_SHIFT;
00448         //v = readServoAlarm(i);
00449         //status |= v<< OpenHRP::RobotHardwareService::SERVO_ALARM_SHIFT;
00450         //v = readDriverTemperature(i);
00451         //status |= v<< OpenHRP::RobotHardwareService::DRIVER_TEMP_SHIFT;
00452         rs->servoState[i][0] = status;
00453         //readExtraServoState(i, (int *)(rs->servoState[i].get_buffer()+1));
00454     }
00455     //readPowerStatus(rs->voltage, rs->current);
00456 }
00457 
00458 void BodyRTC::getStatus2(OpenHRP::RobotHardwareService::RobotState2* rs) {
00459 }
00460 
00461 bool BodyRTC::setServoErrorLimit(const char *i_jname, double i_limit)
00462 {
00463     Link *l = NULL;
00464     if (strcmp(i_jname, "all") == 0 || strcmp(i_jname, "ALL") == 0){
00465         for (unsigned int i=0; i<numJoints(); i++){
00466             m_servoErrorLimit[i] = i_limit;
00467         }
00468     }else if ((l = link(i_jname))){
00469         m_servoErrorLimit[l->jointId] = i_limit;
00470     }else{
00471         char *s = (char *)i_jname; while(*s) {*s=toupper(*s);s++;}
00472         const std::vector<int> jgroup = m_jointGroups[i_jname];
00473         if (jgroup.size()==0) return false;
00474         for (unsigned int i=0; i<jgroup.size(); i++){
00475             m_servoErrorLimit[jgroup[i]] = i_limit;
00476         }
00477     }
00478     return true;
00479 }
00480 
00481 char *time_string()
00482 {
00483     struct timeval tv;
00484     gettimeofday(&tv, NULL);
00485     struct tm *tm_ = localtime(&tv.tv_sec);
00486     static char time[20];
00487     sprintf(time, "%02d:%02d:%02d.%06d", tm_->tm_hour, tm_->tm_min, tm_->tm_sec, (int)tv.tv_usec);
00488     return time;
00489 }
00490 
00491 #define ON              1
00492 #define OFF             0
00493 bool BodyRTC::checkEmergency(emg_reason &o_reason, int &o_id) {
00494     int state;
00495 
00496     o_reason = EMG_NONE; // clear
00497     o_id = -1;
00498 
00499     for (unsigned int i=0; i<numJoints(); i++){
00500         state = readServoState(i);
00501         if (state == ON && m_servoErrorLimit[i] != 0){
00502             double angle, command;
00503             angle = angles[i];
00504             command = commands[i];
00505             if (fabs(angle-command) > m_servoErrorLimit[i]){
00506                 std::cerr << time_string()
00507                           << ": servo error limit over: joint = "
00508                           << joint(i)->name
00509                           << ", qRef = " << command/M_PI*180 << "[deg], q = "
00510                           << angle/M_PI*180 << "[deg]" << std::endl;
00511                 o_reason = EMG_SERVO_ERROR;
00512                 o_id = i;
00513                 return true;
00514             }
00515         }
00516     }
00517     return false;
00518 }
00519 
00520 bool BodyRTC::preOneStep() {
00521     // Simulate servo off in HighGain mode simulation
00522     hrp::Vector3 g(0, 0, 9.8);
00523     calcCM();
00524     rootLink()->calcSubMassCM();
00525     bool all_servo_off = true;
00526     bool emulate_highgain_servo_off_mode = (numJoints() > 0); // If no joints, do not use servo off emulation
00527     for(unsigned int i = 0; i < numJoints(); ++i){
00528         Link *j = joint(i);
00529         commands[i] = j->q;
00530         int p = readPowerState(i);
00531         int s = readServoState(i);
00532         if ( p && s ) { all_servo_off = false; continue; }
00533         switch(j->jointType){
00534             case Link::ROTATIONAL_JOINT:
00535                 {
00536                     j->q += (j->subm*g).cross(j->submwc / j->subm - j->p).dot(j->R * j->a) *0.005*0.01;
00537                     if ( j->q < j->llimit ) {
00538                         j->q = j->llimit;
00539                     }else if ( j->q > j->ulimit ) {
00540                         j->q = j->ulimit;
00541                     }
00542                 }
00543                 break;
00544 
00545             default:
00546                 std::cerr << "calcCMJacobian() : unsupported jointType("
00547                           << j->jointType << std::endl;
00548         }
00549     }
00550     if ( m_resetPosition ) {
00551         getDefaultRootPosition(m_lastServoOn_p, m_lastServoOn_R);
00552         rootLink()->p = m_lastServoOn_p;
00553         rootLink()->setAttitude(m_lastServoOn_R);
00554         m_resetPosition = false;
00555     }
00556     if (emulate_highgain_servo_off_mode) {
00557         if ( all_servo_off ) { // when all servo is off, do not move root joint
00558             rootLink()->p = m_lastServoOn_p;
00559             rootLink()->setAttitude(m_lastServoOn_R);
00560         } else {
00561             m_lastServoOn_p = rootLink()->p;
00562             m_lastServoOn_R = rootLink()->attitude();
00563         }
00564     }
00565 }
00566 
00567 bool BodyRTC::postOneStep() {
00568 
00569     for(unsigned int i = 0; i < numJoints(); ++i){
00570         angles[i] = joint(i)->q;
00571     }
00572     for(unsigned int i = 0; i < numSensors(hrp::Sensor::ACCELERATION); i++ ){
00573         hrp::AccelSensor *s = sensor<AccelSensor>(i);
00574         accels[i][0] =  s->dv[0];
00575         accels[i][1] =  s->dv[1];
00576         accels[i][2] =  s->dv[2];
00577     }
00578     for(unsigned int i = 0; i < numSensors(hrp::Sensor::RATE_GYRO); i++ ){
00579         hrp::RateGyroSensor *s = sensor<RateGyroSensor>(i);
00580         gyros[i][0] =  s->w[0];
00581         gyros[i][1] =  s->w[1];
00582         gyros[i][2] =  s->w[2];
00583     }
00584     for(unsigned int i = 0; i < numSensors(hrp::Sensor::FORCE); i++ ){
00585         hrp::ForceSensor *s = sensor<ForceSensor>(i);
00586         forces[i][0] =  s->f[0];
00587         forces[i][1] =  s->f[1];
00588         forces[i][2] =  s->f[2];
00589         forces[i][3] =  s->tau[0];
00590         forces[i][4] =  s->tau[1];
00591         forces[i][5] =  s->tau[2];
00592     }
00593     if ( checkEmergency(m_emergencyReason, m_emergencyId) ) {
00594         servo("all", false);
00595     }
00596     return true;
00597 }
00598 
00599 // lib/io/iob.h:
00600 #define JID_ALL -1
00601 #define JID_INVALID -2
00602 // these code are copied from rtc/RobotHardware/robot.cpp
00603 bool BodyRTC::servo(const char *jname, bool turnon)
00604 {
00605     Link *l = NULL;
00606     if (strcmp(jname, "all") == 0 || strcmp(jname, "ALL") == 0){
00607         bool ret = true;
00608         for (unsigned int i=0; i<numJoints(); i++){
00609             ret = ret && servo(i, turnon);
00610         }
00611         return ret;
00612     }else if ((l = link(jname))){
00613         return servo(l->jointId, turnon);
00614     }else{
00615         char *s = (char *)jname; while(*s) {*s=toupper(*s);s++;}
00616         const std::vector<int> jgroup = m_jointGroups[jname];
00617         if (jgroup.size() == 0) return false;
00618         bool ret = true;
00619         for (unsigned int i=0; i<jgroup.size(); i++){
00620             ret = ret && servo(jgroup[i], turnon);
00621             return ret;
00622         }
00623     }
00624     return false;
00625 }
00626 
00627 bool BodyRTC::power(const char *jname, bool turnon)
00628 {
00629     int jid = JID_INVALID;
00630 
00631     if (strcmp(jname, "all") == 0 || strcmp(jname, "ALL") == 0){
00632         jid = JID_ALL;
00633     }else{
00634         Link *l = link(jname);
00635         if (!l) return false;
00636         jid = l->jointId;
00637     }
00638     return power(jid, turnon);
00639 }
00640 
00641 RobotHardwareServicePort::RobotHardwareServicePort() {
00642 }
00643 RobotHardwareServicePort::~RobotHardwareServicePort() {
00644 }
00645 
00646 void RobotHardwareServicePort::getStatus(OpenHRP::RobotHardwareService::RobotState_out rs) {
00647     rs = new OpenHRP::RobotHardwareService::RobotState();
00648     m_robot->getStatus(rs);
00649 }
00650 
00651 void RobotHardwareServicePort::getStatus2(OpenHRP::RobotHardwareService::RobotState2_out rs) {
00652     rs = new OpenHRP::RobotHardwareService::RobotState2();
00653     m_robot->getStatus2(rs);
00654 }
00655 
00656 CORBA::Boolean RobotHardwareServicePort::power(const char* jname, OpenHRP::RobotHardwareService::SwitchStatus turnon) {
00657     m_robot->power(jname, turnon == OpenHRP::RobotHardwareService::SWITCH_ON);
00658 }
00659 
00660 CORBA::Boolean RobotHardwareServicePort::servo(const char* jname, OpenHRP::RobotHardwareService::SwitchStatus turnon) {
00661     m_robot->servo(jname, turnon == OpenHRP::RobotHardwareService::SWITCH_ON);
00662 }
00663 void RobotHardwareServicePort::setServoGainPercentage(const char *jname, double limit) {
00664 }
00665 void RobotHardwareServicePort::setServoErrorLimit(const char *jname, double limit) {
00666     m_robot->setServoErrorLimit(jname, limit);
00667 }
00668 void RobotHardwareServicePort::calibrateInertiaSensor() {
00669 }
00670 void RobotHardwareServicePort::removeForceSensorOffset() {
00671 }
00672 void RobotHardwareServicePort::initializeJointAngle(const char* name, const char* option) {
00673 }
00674 CORBA::Boolean RobotHardwareServicePort::addJointGroup(const char* gname, const OpenHRP::RobotHardwareService::StrSequence& jnames) {
00675     char *s = (char *)gname; while(*s) {*s=toupper(*s);s++;}
00676     std::vector<int> jids;
00677     std::vector<std::string> joints;
00678     joints.resize(jnames.length());
00679     for (unsigned int i=0; i<jnames.length(); i++){
00680         joints[i] = jnames[i];
00681     }
00682     bool ret = m_robot->names2ids(joints, jids);
00683     //m_jointGroups[gname] = jids;
00684     m_robot->addJointGroup(gname, jids);
00685     return ret;
00686 }
00687 CORBA::Boolean RobotHardwareServicePort::readDigitalInput(::OpenHRP::RobotHardwareService::OctSequence_out din) {
00688     return false;
00689 }
00690 CORBA::Long RobotHardwareServicePort::lengthDigitalInput() {
00691     return 0;
00692 }
00693 CORBA::Boolean RobotHardwareServicePort::writeDigitalOutput(const ::OpenHRP::RobotHardwareService::OctSequence& dout) {
00694     return false;
00695 }
00696 CORBA::Boolean RobotHardwareServicePort::writeDigitalOutputWithMask(const ::OpenHRP::RobotHardwareService::OctSequence& dout, const ::OpenHRP::RobotHardwareService::OctSequence& mask) {
00697     return false;
00698 }
00699 CORBA::Long RobotHardwareServicePort::lengthDigitalOutput() {
00700     return 0;
00701 }
00702 CORBA::Boolean RobotHardwareServicePort::readDigitalOutput(::OpenHRP::RobotHardwareService::OctSequence_out dout) {
00703     return false;
00704 }
00705 //
00706 void RobotHardwareServicePort::setRobot(BodyRTC *i_robot) { m_robot = i_robot; }
00707 
00708 template <class _Delete>
00709 void DummyDelete(RTC::RTObject_impl* rtc)
00710 {
00711     // BodyRTC will be released when BodyPtr is released
00712 }
00713 
00714 void BodyRTC::moduleInit(RTC::Manager* manager)
00715 {
00716     coil::Properties profile(bodyrtc_spec);
00717     manager->registerFactory(profile,
00718                              RTC::Create<BodyRTC>,
00719                              DummyDelete<BodyRTC>
00720                              //RTC::Delete<BodyRTC>
00721         );
00722 }


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Wed Sep 6 2017 02:35:54