Quadrotor_tk_Handler.cpp
Go to the documentation of this file.
00001 
00002 #include <pluginlib/class_list_macros.h>
00003 #include <vrep_ros_plugin/GenericObjectHandler.h>
00004 #include <quadrotor_tk_handler/Quadrotor_tk_Handler.h>
00005 #include <stdio.h>
00006 #include <v_repLib.h>
00007 
00008 #include <telekyb_msgs/TKState.h>
00009 #include <sensor_msgs/Imu.h>
00010 
00011 #include <eigen3/Eigen/Geometry>
00012 
00013 #include <vrep_ros_plugin/access.h>
00014 #include <vrep_ros_plugin/ConsoleHandler.h>
00015 
00016 Quadrotor_tk_Handler::Quadrotor_tk_Handler() : GenericObjectHandler(),
00017 _torqueToForceRatio(0.01738),
00018 _handleOfCoM(-1),
00019 _ctrlMode(CustomDataHeaders::DIRECT),
00020 _tkMotorCommands(4,0),
00021 //_tkCommands(3,0),
00022 _quadrotorMass(1.0),
00023 // Before changing the following 3 parameters be careful and look closely into the controller which is implemented below
00024 _att_cutoff(5.0),
00025 _att_damping(0.42),
00026 _kp_yaw(1),
00027 _lastReceivedCmdTime(ros::Time::now()),
00028 _previousTime(ros::Time::now()),
00029 _integralTermRoll(0.0),
00030 _integralTermPitch(0.0)
00031 {
00032 }
00033 
00034 Quadrotor_tk_Handler::~Quadrotor_tk_Handler(){
00035 }
00036 
00037 unsigned int Quadrotor_tk_Handler::getObjectType() const {
00038         return CustomDataHeaders::QUADROTOR_TK_DATA_MAIN;
00039 }
00040 
00041 /*void Quadrotor_tk_Handler::setID(int newID){
00042     _id=newID;
00043 }
00044 
00045 int Quadrotor_tk_Handler::getID(){
00046     return(_id);
00047 }*/
00048 
00049 /*
00050 void Quadrotor_tk_Handler::setAssociatedObject(int objID,int objUniqueID){
00051     _associatedObjectID=objID;
00052     _associatedObjectUniqueID=objUniqueID;
00053 }
00054 
00055 int Quadrotor_tk_Handler::getAssociatedObject(){
00056     return(_associatedObjectID);
00057 }
00058 
00059 int Quadrotor_tk_Handler::getAssociatedObjectUniqueId(){
00060     return(_associatedObjectUniqueID);
00061 }
00062 
00063 void Quadrotor_tk_Handler::synchronizeSceneObject(){
00064     // We update Quadrotor_tk_Handler's associated scene object custom data:
00065     putQuadrotorTagToSceneObject(_associatedObjectID,_torqueToForceRatio);
00066 }
00067  */
00068 
00069 void Quadrotor_tk_Handler::synchronize(){
00070         //    // We update Quadrotor_tk_Handler's data from its associated scene object custom data:
00071         //    // 1. Get all the developer data attached to the associated scene object (this is custom data added by the developer):
00072         //    int buffSize=simGetObjectCustomDataLength(_associatedObjectID,CustomDataHeaders::DEVELOPER_DATA_HEADER);
00073         //    char* datBuff=new char[buffSize];
00074         //    simGetObjectCustomData(_associatedObjectID,CustomDataHeaders::DEVELOPER_DATA_HEADER,datBuff);
00075         //    std::vector<unsigned char> developerCustomData(datBuff,datBuff+buffSize);
00076         //    delete[] datBuff;
00077         //    // 2. From that retrieved data, try to extract sub-data with the QUADROTOR_DATA_TF_RATIO tag:
00078         //    std::vector<unsigned char> tempMainData;
00079         //    if (CAccess::extractSerializationData(developerCustomData,CustomDataHeaders::QUADROTOR_DATA_TF_RATIO,tempMainData))
00080         //    { // Yes, the tag is there. For now we only have to synchronize _maxVelocity:
00081         //        _torqueToForceRatio=CAccess::pop_float(tempMainData);
00082         //        std::cout << "torque to force ratio: " << _torqueToForceRatio << std::endl;
00083         //    }
00084 
00085 
00086         simFloat intertia[9];
00087         simFloat compos[3];
00088 
00089         // Get the mass of the quadcopter
00090         simGetShapeMassAndInertia(_associatedObjectID,&_quadrotorMass,intertia,compos,NULL);
00091 
00092         // Remove # chars for compatibility with ROS
00093         _associatedObjectName = simGetObjectName(_associatedObjectID);
00094         std::string objectName(_associatedObjectName);
00095         std::replace( objectName.begin(), objectName.end(), '#', '_');
00096 
00097         // Publisher of the quadropter status
00098         _pub = _nh.advertise<telekyb_msgs::TKState>(objectName+"/status", 1000);
00099 
00100         // Publisher of the IMU
00101         _pubIMU = _nh.advertise<sensor_msgs::Imu>(objectName+"/IMU", 1000);
00102 
00103         // Subscriber of the command from TeleKib
00104         //_sub = _nh.subscribe("/Telekyb/TelekybCore_0/Commands", 1000, &Quadrotor_tk_Handler::tkMotorCommandsCallback, this);
00105 }
00106 
00107 
00108 //void Quadrotor_tk_Handler::setThrustToForceRatio(float thrustToForceRatio){
00109 //    _torqueToForceRatio=thrustToForceRatio;
00110 //    synchronizeSceneObject(); // make sure the associated scene object has the same values stored as this
00111 //}
00112 //
00113 //float Quadrotor_tk_Handler::getThrustToForceRatio(){
00114 //    return(_torqueToForceRatio);
00115 //}
00116 
00117 //void Quadrotor_tk_Handler::putQuadrotorTagToSceneObject(int objectHandle,float torqueToForceRatio){
00118 //    // This creates/updates a QUADROTOR_DATA_MAIN tag
00119 //    // 1. Get all the developer data attached to the associated scene object (this is custom data added by the developer):
00120 //    int buffSize=simGetObjectCustomDataLength(objectHandle,DEVELOPER_DATA_HEADER);
00121 //    char* datBuff=new char[buffSize];
00122 //    simGetObjectCustomData(objectHandle,DEVELOPER_DATA_HEADER,datBuff);
00123 //    std::vector<unsigned char> developerCustomData(datBuff,datBuff+buffSize);
00124 //    delete[] datBuff;
00125 //    // 2. From that retrieved data, extract sub-data with the QUADROTOR_DATA_MAIN tag, update it, and add it back to the retrieved data:
00126 //    std::vector<unsigned char> tempMainData;
00127 //    CAccess::extractSerializationData(developerCustomData,QUADROTOR_DATA_MAIN,tempMainData);
00128 //    tempMainData.clear(); // we discard the old value (if present)
00129 //    CAccess::push_float(tempMainData,torqueToForceRatio); // we replace it with the new value
00130 //    CAccess::insertSerializationData(developerCustomData,QUADROTOR_DATA_MAIN,tempMainData);
00131 //    // 3. We add/update the scene object with the updated custom data:
00132 //    simAddObjectCustomData(objectHandle,DEVELOPER_DATA_HEADER,(simChar*)&developerCustomData[0],int(developerCustomData.size()));
00133 //}
00134 
00135 void Quadrotor_tk_Handler::handleSimulation(){
00136         // called when the main script calls: simHandleModule (it is called time by time)
00137         if(!_initialized){
00138                 _initialize();
00139         }
00140 
00141         // TimeStep Computation
00142         ros::Time now = ros::Time::now();
00143         ros::Duration timeStep = now - _previousTime;
00144         //DEBUG
00145         //      std::cout<< "DEBUG: TimeStep: " << timeStep << std::endl;
00146 
00147         // Position of the quadrotor (x,y,z)
00148         Eigen::Matrix<simFloat, 3, 1> position;
00149         // Orientation of the quadrotor
00150         Eigen::Quaternion< simFloat > orientation; //(x,y,z,w)
00151         Eigen::Matrix<simFloat, 3, 1> linVelocity;
00152         Eigen::Matrix<simFloat, 3, 1> angVelocity;
00153         const static Eigen::Quaternion< simFloat > nwuToNed(0,1,0,0);
00154 
00155         if(simGetObjectPosition(_handleOfCoM, -1, position.data())!=-1 &&
00156                         simGetObjectQuaternion(_handleOfCoM, -1, orientation.coeffs().data())!=-1 &&
00157                         simGetObjectVelocity(_handleOfCoM, linVelocity.data(), angVelocity.data())!=-1){
00158                 //DEBUG
00159                 //std::cout<<"DEBUG: Rotation ";
00160 
00161                 position = nwuToNed*position;
00162                 linVelocity = nwuToNed*linVelocity;
00163                 angVelocity = orientation.conjugate()*angVelocity; // Express angular velocity in body frame
00164                 orientation = nwuToNed*orientation; // change world frame to north-east-down
00165 
00166 
00167                 //angVelocity = nwuToNed*angVelocity;
00168                 // use only positive w (not necessary)
00169                 if (orientation.w()<0){
00170                         orientation.coeffs() *=-1;
00171                 }
00172 
00173                 // Fill the status msg
00174                 telekyb_msgs::TKState msg;
00175                 msg.header.stamp = now;
00176                 msg.pose.position.x = position[0];
00177                 msg.pose.position.y = position[1];
00178                 msg.pose.position.z = position[2];
00179                 msg.pose.orientation.w = orientation.w();
00180                 msg.pose.orientation.x = orientation.x();
00181                 msg.pose.orientation.y = orientation.y();
00182                 msg.pose.orientation.z = orientation.z();
00183                 msg.twist.linear.x = linVelocity[0];
00184                 msg.twist.linear.y = linVelocity[1];
00185                 msg.twist.linear.z = linVelocity[2];
00186                 msg.twist.angular.x = angVelocity[0];
00187                 msg.twist.angular.y = angVelocity[1];
00188                 msg.twist.angular.z = angVelocity[2];
00189                 std::stringstream ss;
00190                 //DEBUG:
00191                 //std::cout << "Filling the TKState msg" << std::endl;
00192                 _pub.publish(msg);
00193         }
00194 
00195         simFloat TotforceZ = 0.0;
00196 
00197         if (_ctrlMode == CustomDataHeaders::DIRECT){
00198                 //DEBUG
00199                 //std::cout<<"DEBUG: DIRECT MODE ";
00200 
00201                 for(uint motorIdx = 0; motorIdx < 4; ++motorIdx){
00202                         const simFloat force[3] = {0.0, 0.0, -(simFloat)_tkMotorCommands[motorIdx]};
00203                         const simFloat torque[3] = {0.0, 0.0, _torqueToForceRatio*(1-2*((int)(motorIdx/2)))*(simFloat)_tkMotorCommands[motorIdx]};
00204 
00205                         // Compute the net force
00206                         TotforceZ =+ -(simFloat)_tkMotorCommands[motorIdx];
00207 
00208                         // Try to apply a force to the object
00209                         if(simAddForce(_associatedObjectID, _jointPosition[motorIdx], force)==-1){
00210                                 simSetLastError( _associatedObjectName.c_str(), "Error applying force.");
00211                         } else if(simAddForceAndTorque(_associatedObjectID, NULL, torque)==-1){
00212                                 simSetLastError( _associatedObjectName.c_str(), "Error applying torque.");
00213                         } else if(simSetJointTargetVelocity(_handleOfJoint[motorIdx], 10*_tkMotorCommands[motorIdx])==-1){
00214                                 simSetLastError( simGetObjectName(_handleOfJoint[motorIdx]), "Error applying velocity.");
00215                         }
00216                 }
00217         } else if (_ctrlMode == CustomDataHeaders::INTERNAL){
00218 
00219                 //              timeStep=now-previousTime;
00220                 //DEBUG
00221                 //              std::cout<<"INTERNAL MODE "<< timeStep;
00222                 //DEBUG
00223                 //std::cout<<"INTERNAL MODE ";
00224 
00225                 // Compute the net force
00226                 TotforceZ = (simFloat)_tkCommands.thrust;
00227 
00228                 //              Eigen::Matrix< simFloat, 3, 1> rpy = orientation.toRotationMatrix().eulerAngles(2,1,0);
00229                 //              Eigen::Matrix< simFloat, 3, 3> rotMatrix = orientation.toRotationMatrix();
00230                 //              Eigen::Matrix< simFloat, 3, 1> rpy(
00231                 //                              atan2(rotMatrix(3,1),rotMatrix(3,2)),
00232                 //                              acos(rotMatrix(3,3)),
00233                 //                              -atan2(rotMatrix(1,3),rotMatrix(2,3)));
00234                 //
00235                 //                              atan2(rotMatrix(3,2),rotMatrix(3,3)),
00236                 //                              atan2(-rotMatrix(3,1),sqrt(rotMatrix(3,2)*rotMatrix(3,2)+rotMatrix(3,3)*rotMatrix(3,3))),
00237                 //                              atan2(rotMatrix(2,1),rotMatrix(1,1)));
00238 
00239                 Eigen::Matrix< simFloat, 3, 3> R = orientation.toRotationMatrix();
00240                 Eigen::Matrix< simFloat, 3, 1> rpy;
00241                 rpy(0) = atan2((double)R(2,1), (double)R(2,2));
00242                 rpy(1) = atan2(-R(2,0), sqrt( R(2,1)*R(2,1) + R(2,2)*R(2,2) ) );
00243                 rpy(2) = atan2((double)R(1,0),(double)R(0,0));
00244 
00245                 //              std::cout << "DEBUG: (_tkCommands.roll): " <<  (_tkCommands.roll) <<std::endl;
00246                 //              std::cout << "DEBUG: rpy: " << rpy(0) << "  "<< rpy(1) << "  " << rpy(2) <<std::endl;
00247                 //              std::cout << "DEBUG: R: " << R <<std::endl;
00248                 //
00249                 //              std::cout << "DEBUG: R(3,1): " << R(3,1) <<std::endl;
00250                 //              std::cout << "DEBUG: R(3,2): " << R(3,2) <<std::endl;
00251                 //              std::cout << "DEBUG: R(3,3): " << R(3,3) <<std::endl;
00252                 // Definition of sin_r,cos_r etc.
00253                 const double cos_r = cos((double)rpy(0));
00254                 //std::cout << "DEBUG: cos_r: " <<  cos_r <<std::endl;
00255                 const double sin_r = sin((double)rpy(0));
00256                 //std::cout << "DEBUG: sin_r: " <<  sin_r <<std::endl;
00257                 const double cos_p = cos((double)rpy(1));
00258                 //std::cout << "DEBUG: cos_p: " <<  cos_p <<std::endl;
00259                 const double sin_p = sin((double)rpy(1));
00260                 //std::cout << "DEBUG: sin_p: " <<  sin_p <<std::endl;
00261                 const double tan_p = tan((double)rpy(1));
00262 
00263                 const Eigen::Matrix<simFloat, 3, 3> angVelToEulerRate = (Eigen::Matrix<simFloat, 3, 3>() <<
00264                                 1.0, sin_r*tan_p, cos_r*tan_p,
00265                                 0.0,       cos_r,      -sin_r,
00266                                 0.0, sin_r/cos_p, cos_r/cos_p).finished();
00267 
00268                 Eigen::Matrix< simFloat, 3, 1> rpyRate = angVelToEulerRate*angVelocity;
00269                 const simFloat kp_att = _att_cutoff;
00270                 const simFloat kd_att = _att_damping;
00271 
00272                 // Errors
00273                 const simFloat errorRoll = (_tkCommands.roll)-(rpy(0));
00274                 const simFloat errorPitch = (_tkCommands.pitch)-(rpy(1));
00275 
00276                 // Debug: the 2 following instructions are needed to give to the quadrotor a commanded
00277                 //                roll angle of 0 deg and a commanded pitch angle of -20 deg.
00278                 //        To apply these angles you should also comment the line:
00279                 //                Eigen::Matrix< simFloat, 3, 1> worldForce = nwuToNed*orientation*Eigen::Matrix< simFloat, 3, 1>(0.0,0.0,(simFloat)_tkCommands.thrust);
00280                 //        and substitute it with the following line:
00281                 //            Eigen::Matrix< simFloat, 3, 1> worldForce = nwuToNed*Eigen::Matrix< simFloat, 3, 1>(0.0,0.0,-9.81);
00282                 //                which is needed to keep the quadrotor at the desired angles.
00283         /*      const simFloat errorRoll = (-40*3.14/180)-(rpy(0));
00284                 const simFloat errorPitch = (-40*3.14/180)-(rpy(1));*/
00285 
00286 
00287                 // Computaton of the integral terms
00288                 _integralTermRoll = _integralTermRoll + timeStep.toSec() * errorRoll;
00289                 _integralTermPitch = _integralTermPitch + timeStep.toSec() * errorPitch;
00290                 if(_integralTermRoll<0.0001)_integralTermRoll=0.0;
00291                 if(_integralTermPitch<0.0001)_integralTermPitch=0.0;
00292 
00293 
00294                 Eigen::Matrix< simFloat, 3, 1> rpyTorque(
00295                                 //roll
00296                                 kp_att*(errorRoll) + kd_att*(0-rpyRate(0))+0*0.001*_integralTermRoll,
00297                                 //pitch
00298                                 //                              0.1*kp_att*(errorPitch) + 0.02*kd_att*(0-rpyRate(1))+0*0.002*_integralTermPitch,
00299                                 kp_att*(errorPitch) + kd_att*(0-rpyRate(1))+0*0.002*_integralTermPitch,
00300                                 //yaw
00301                                 _kp_yaw*(_tkCommands.yaw- rpyRate(2)));  //sign is the opposite of the yaw angular velocity
00302 
00303                 //DEBUG
00304                 //              std::cout << "DEBUG: (_tkCommands.roll): " <<  (_tkCommands.roll) <<std::endl;
00305                 //              std::cout << "DEBUG: rpy: " << rpy(0) << "  "<< rpy(1) << "  " << rpy(2) <<std::endl;
00306                 //              std::cout << "DEBUG: sin(_tkCommands.pitch): " <<  sin(_tkCommands.pitch) <<std::endl;
00307                 //              std::cout << "DEBUG: sin(rpy(1)): " << sin(rpy(1)) <<std::endl;
00308                 //              std::cout << "DEBUG: errorRoll: " << errorRoll <<std::endl;
00309                 //              std::cout << "DEBUG: errorPitch: " << errorPitch <<std::endl;
00310 //              std::cout <<  _associatedObjectName.c_str() << " " << "_tkCommands.yaw: " << _tkCommands.yaw <<std::endl;
00311 //              std::cout <<  _associatedObjectName.c_str() << " " << "rpyRate(2): " << rpyRate(2) <<std::endl;
00312 
00313                 rpyTorque = nwuToNed*orientation*rpyTorque; //rotate torque to world frame
00314                 //const Eigen::Matrix< simFloat, 3, 1> worldForce = nwuToNed*Eigen::Matrix< simFloat, 3, 1>(0.0,0.0,(simFloat)_tkCommands.thrust);
00315 
00316                 Eigen::Matrix< simFloat, 3, 1> worldForce = nwuToNed*orientation*Eigen::Matrix< simFloat, 3, 1>(0.0,0.0,(simFloat)_tkCommands.thrust);
00317 
00318 //              Eigen::Matrix< simFloat, 3, 1> worldForce = nwuToNed*Eigen::Matrix< simFloat, 3, 1>(0.0,0.0,-9.81);
00319                 // To Delete Probably
00320                 //              if(worldForce(0)<0.001 && worldForce(0)>-0.001)worldForce(0)=0;
00321                 //              if(worldForce(1)<0.001 && worldForce(1)>-0.001)worldForce(1)=0;
00322 
00323 
00324                 //DEBUG torques and forces
00325                 //              std::cout << "DEBUG: rpyTorque: " << rpyTorque(0) <<"|"<< rpyTorque(1) <<"|"<< rpyTorque(2) <<"|" <<std::endl;
00326                 //              std::cout << "DEBUG: forces: " << worldForce(0) <<"|"<< worldForce(1) <<"|"<< worldForce(2) <<"|" <<std::endl;
00327 
00328                 //        std::stringstream ss;
00329                 //        ss << "applying force : [" << worldForce.transpose() << std::endl;
00330                 //        ConsoleHandler::printInConsole(ss);
00331                 if(simAddForceAndTorque(_associatedObjectID, worldForce.data(), rpyTorque.data())==-1){
00332                         //                                                      if(simAddForceAndTorque(_associatedObjectID, worldForce.data(), 0)==-1){
00333                         simSetLastError( _associatedObjectName.c_str(), "Error applying force.");
00334                 } else {
00335                         for (uint motorIdx = 0; motorIdx < 4; ++motorIdx){
00336                                 // the following is needed to rotate the propellers
00337                                 if(simSetJointTargetVelocity(_handleOfJoint[motorIdx], _tkCommands.thrust)==-1){
00338                                         simSetLastError( simGetObjectName(_handleOfJoint[motorIdx]), "Error applying velocity.");
00339                                 }
00340                         }
00341                 }
00342                 _previousTime=now;
00343         }
00344 
00345         Eigen::Matrix<simFloat, 3, 1> TotCommandforces(0.0, 0.0, TotforceZ);
00346         Eigen::Matrix<simFloat, 3, 1> VectorG (0.0, 0.0, 9.8);
00347         VectorG = orientation.conjugate()*VectorG; // Express angular velocity in body frame
00348 
00349         // Fill the IMU msg
00350         sensor_msgs::Imu msg1;
00351         msg1.header.stamp = ros::Time::now();
00352         msg1.angular_velocity.x = angVelocity[0];
00353         msg1.angular_velocity.y = angVelocity[1];
00354         msg1.angular_velocity.z = angVelocity[2];
00355         msg1.linear_acceleration.x = TotCommandforces[0]/_quadrotorMass + VectorG[0];
00356         msg1.linear_acceleration.y = TotCommandforces[1]/_quadrotorMass + VectorG[1];
00357         msg1.linear_acceleration.z = TotCommandforces[2]/_quadrotorMass + VectorG[2];
00358 
00359         Eigen::Vector3d acc(msg1.linear_acceleration.x, msg1.linear_acceleration.y, msg1.linear_acceleration.z);
00360         Eigen::Quaterniond q = Eigen::Quaterniond::FromTwoVectors(acc, Eigen::Vector3d(0,0,1));
00361         msg1.orientation.w = q.w();
00362         msg1.orientation.x = q.x();
00363         msg1.orientation.y = q.y();
00364         msg1.orientation.z = q.z();
00365 
00366         _pubIMU.publish(msg1); // Publish the Imu message in ROS
00367 
00368         if ((now-_lastReceivedCmdTime).toSec() > 0.1){
00369                 _tkMotorCommands = std::vector<double>(4,0);
00370                 _tkCommands.pitch = 0.0;
00371                 _tkCommands.roll = 0.0;
00372                 _tkCommands.yaw = 0.0;
00373                 _tkCommands.thrust = 0.0;//_quadrotorMass*9.8;
00374                 // Debug Print
00375                 //              std::stringstream ss;
00376                 //              ss << "I am here" << std::endl;
00377                 //              simAddStatusbarMessage(ss.str().c_str());
00378                 //              ConsoleHandler::printInConsole(ss);
00379                 if ((now-_lastPrintedMsg).toSec() >= 1){
00380                         std::stringstream ss;
00381                         ss << "- [" << _associatedObjectName << "] No command received since more than " << (now-_lastReceivedCmdTime).toSec() << "s!" << std::endl;
00382                         simAddStatusbarMessage(ss.str().c_str());
00383                         ConsoleHandler::printInConsole(ss);
00384                         _lastPrintedMsg = now;
00385                 }
00386         }
00387 
00388         //    if ((now-_lastPrintedMsg).toSec() >= 1){
00389         //        std::stringstream sstream("I am alive at simulation time = ");
00390         //        sstream << simGetSimulationTime() << std::endl;
00391         //        simAddStatusbarMessage(sstream.str().c_str());
00392         //        _lastPrintedMsg = now;
00393         //    }
00394 }
00395 
00396 
00397 void Quadrotor_tk_Handler::_initialize(){
00398         if (_initialized)
00399                 return;
00400 
00401         // get some data from the main object
00402         std::vector<unsigned char> developerCustomData;
00403         getDeveloperCustomData(developerCustomData);
00404 
00405         // 2. From that retrieved data, try to extract sub-data with the IMU_DATA_MAIN tag:
00406         std::vector<unsigned char> tempMainData;
00407         std::stringstream ss;
00408 
00409         if (CAccess::extractSerializationData(developerCustomData, CustomDataHeaders::IMU_DATA_MASS,tempMainData)){
00410                 //      if (false){
00411                 _quadrotorMass=CAccess::pop_float(tempMainData);
00412                 ss << "- [" << _associatedObjectName << "] Setting mass to: " << _quadrotorMass << "." << std::endl;
00413         } else {
00414                 _quadrotorMass = 24.0;
00415                 ss << "- [" << _associatedObjectName << "] Mass of the quadrotor not specified. using " << _quadrotorMass << " as default."  << std::endl;
00416         }
00417 
00418         if (CAccess::extractSerializationData(developerCustomData, CustomDataHeaders::QUADROTOR_DATA_TF_RATIO,tempMainData)){
00419                 _torqueToForceRatio=CAccess::pop_float(tempMainData);
00420                 ss << "- [" << _associatedObjectName << "] Setting torque to force ratio to: " << _torqueToForceRatio << "." << std::endl;
00421         } else {
00422                 _torqueToForceRatio = 0.01738;
00423                 ss << "- [" << _associatedObjectName << "] Torque to force ratio not specified. using " << _torqueToForceRatio << " as default."  << std::endl;
00424         }
00425 
00426         if (CAccess::extractSerializationData(developerCustomData, CustomDataHeaders::QUADROTOR_DATA_CTRL_MODE,tempMainData)){
00427                 const int ctrlMode = CAccess::pop_int(tempMainData);
00428                 if (ctrlMode == (int)(CustomDataHeaders::DIRECT)){
00429                         _ctrlMode = CustomDataHeaders::DIRECT;
00430                         ss << "- [" << _associatedObjectName << "] Using DIRECT control mode." << std::endl;
00431                 } else if (ctrlMode == (int)(CustomDataHeaders::INTERNAL)){
00432                         _ctrlMode = CustomDataHeaders::INTERNAL;
00433                         ss << "- [" << _associatedObjectName << "] Using INTERNAL control mode." << std::endl;
00434                 } else {
00435                         _ctrlMode = CustomDataHeaders::DIRECT;
00436                         ss << "- [" << _associatedObjectName << "] Invalid control mode specified. using DIRECT as default." << std::endl;
00437                 }
00438 
00439         } else {
00440                 _ctrlMode = CustomDataHeaders::DIRECT;
00441                 ss << "- [" << _associatedObjectName << "] Control mode not specified. using DIRECT as default."  << std::endl;
00442         }
00443 
00444         // We need to find the handle of quadrotor motors, and CoM.
00445         for(uint motorIdx = 0; motorIdx < 4; ++motorIdx){
00446                 _handleOfJoint[motorIdx] = -1;
00447         }
00448         std::vector<int> toExplore;
00449         toExplore.push_back(_associatedObjectID); // We start exploration with the base of the quadrotor-tree
00450         while (toExplore.size()!=0)
00451         {
00452                 int objHandle=toExplore[toExplore.size()-1];
00453                 toExplore.pop_back();
00454                 // 1. Add this object's children to the list to explore:
00455                 int index=0;
00456                 int childHandle=simGetObjectChild(objHandle,index++);
00457                 while (childHandle!=-1) {
00458                         toExplore.push_back(childHandle);
00459                         //            std::cout << "Adding " << simGetObjectName(childHandle) << " to exploration list." << std::endl;
00460                         childHandle=simGetObjectChild(objHandle,index++);
00461                 }
00462                 // 2. Now check if this object has one of the tags we are looking for:
00463                 // a. Get all the developer data attached to this scene object (this is custom data added by the developer):
00464                 int buffSize=simGetObjectCustomDataLength(objHandle,CustomDataHeaders::DEVELOPER_DATA_HEADER);
00465                 if (buffSize!=0) { // Yes there is some custom data written by us (the developer with the DEVELOPER_DATA_HEADER header)
00466                         char* datBuff=new char[buffSize];
00467                         simGetObjectCustomData(objHandle,CustomDataHeaders::DEVELOPER_DATA_HEADER,datBuff);
00468                         std::vector<unsigned char> developerCustomData(datBuff,datBuff+buffSize);
00469                         delete[] datBuff;
00470                         // b. From that retrieved data, try to extract sub-data with the searched tags:
00471                         std::vector<unsigned char> quadrotorTagData;
00472                         for (uint motorIdx = 0; motorIdx < 4; ++motorIdx){
00473                                 if (CAccess::extractSerializationData(developerCustomData,CustomDataHeaders::QUADROTOR_DATA_MOTOR_0+motorIdx,quadrotorTagData)){
00474                                         _handleOfJoint[motorIdx]=objHandle; // We found the QUADROTOR_DATA_MOTOR_i tag. This is the i-th motor!
00475                                         simGetObjectPosition(objHandle,_associatedObjectID,_jointPosition[motorIdx]);
00476                                         ss << "- [" << _associatedObjectName << "] Found motor " << motorIdx << " in position ["
00477                                                         << _jointPosition[motorIdx][0] << ", "
00478                                                         << _jointPosition[motorIdx][1] << ", "
00479                                                         << _jointPosition[motorIdx][2] << "]." <<  std::endl;
00480                                 }
00481                         }
00482                         if (CAccess::extractSerializationData(developerCustomData,CustomDataHeaders::QUADROTOR_DATA_COM,quadrotorTagData)){
00483                                 _handleOfCoM=objHandle; // We found the QUADROTOR_DATA_MOTOR_i tag. This is the i-th motor!
00484                                 ss << "- [" << _associatedObjectName << "] Found CENTER OF MASS in '"<< simGetObjectName(objHandle) <<"'." << std::endl;
00485                         }
00486                 }
00487         }
00488 
00489 
00490         // Subscriber of the command from TeleKib
00491         std::string objectName(_associatedObjectName);
00492         std::replace( objectName.begin(), objectName.end(), '#', '_');
00493 
00494         if (_ctrlMode == CustomDataHeaders::DIRECT){
00495                 try{
00496                         _sub = _nh.subscribe(objectName+"/Commands", 1000, &Quadrotor_tk_Handler::tkMotorCommandsCallback, this);
00497                 } catch (ros::Exception &e) {
00498                         std::stringstream ss(e.what());
00499                         ss << std::endl;
00500                         ConsoleHandler::printInConsole(ss);
00501                 }
00502 
00503         } else if (_ctrlMode == CustomDataHeaders::INTERNAL){
00504                 try{
00505                         std::string objectIdExtracted = objectName.substr(objectName.find('_')+1,objectName.size());
00506 
00507                         std::cout<< std::endl << "- [" << objectName <<"] Subscribed for Commands (INTERNAL mode) on the ROS Topic: ";
00508                         std::string rosTopicCommands = "/TeleKyb/TeleKybCore_" + objectIdExtracted + "/Commands";
00509                         std::cout << rosTopicCommands << std::endl;
00510 
00511                         // Subscribe to the Right topic according to the objectName.
00512                         _sub = _nh.subscribe(rosTopicCommands, 1000, &Quadrotor_tk_Handler::tkCommandsCallback, this);
00513 
00514                         // Example of right subscription for the object with objectName 'quadrotor_0'
00515                         //_sub = _nh.subscribe("/TeleKyb/TeleKybCore_0/Commands", 1000, &Quadrotor_tk_Handler::tkCommandsCallback(), this)
00516 
00517                 } catch (ros::Exception &e) {
00518                         std::stringstream ss(e.what());
00519                         ss << std::endl;
00520                         ConsoleHandler::printInConsole(ss);
00521                 }
00522         } else {
00523                 simSetLastError( _associatedObjectName.c_str(), "Unknown control mode.");
00524         }
00525 
00526 
00527 
00528         ConsoleHandler::printInConsole(ss);
00529         _initialized=true;
00530 }
00531 
00532 void Quadrotor_tk_Handler::tkMotorCommandsCallback(const telekyb_msgs::TKMotorCommands::ConstPtr& msg){
00533         if (msg->force.size() == 4){
00534                 _tkMotorCommands = msg->force;
00535                 _lastReceivedCmdTime = ros::Time::now();
00536         } else {
00537                 simSetLastError( _associatedObjectName.c_str(), "Received wrong command size.");
00538                 //        std::cout << "Received wrong command containing " <<  msg->force.size() << " elements" << std::endl;
00539         }
00540 }
00541 
00542 void Quadrotor_tk_Handler::tkCommandsCallback(const telekyb_msgs::TKCommands::ConstPtr& msg){
00543         _tkCommands = *msg;
00544         _lastReceivedCmdTime = ros::Time::now();
00545 }
00546 
00547 
00548 PLUGINLIB_EXPORT_CLASS(Quadrotor_tk_Handler, GenericObjectHandler)
00549 
00550 
00551 
00552 


quadrotor_tk_handler
Author(s):
autogenerated on Sat Jun 8 2019 20:22:54