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
00022 _quadrotorMass(1.0),
00023
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
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060
00061
00062
00063
00064
00065
00066
00067
00068
00069 void Quadrotor_tk_Handler::synchronize(){
00070
00071
00072
00073
00074
00075
00076
00077
00078
00079
00080
00081
00082
00083
00084
00085
00086 simFloat intertia[9];
00087 simFloat compos[3];
00088
00089
00090 simGetShapeMassAndInertia(_associatedObjectID,&_quadrotorMass,intertia,compos,NULL);
00091
00092
00093 _associatedObjectName = simGetObjectName(_associatedObjectID);
00094 std::string objectName(_associatedObjectName);
00095 std::replace( objectName.begin(), objectName.end(), '#', '_');
00096
00097
00098 _pub = _nh.advertise<telekyb_msgs::TKState>(objectName+"/status", 1000);
00099
00100
00101 _pubIMU = _nh.advertise<sensor_msgs::Imu>(objectName+"/IMU", 1000);
00102
00103
00104
00105 }
00106
00107
00108
00109
00110
00111
00112
00113
00114
00115
00116
00117
00118
00119
00120
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134
00135 void Quadrotor_tk_Handler::handleSimulation(){
00136
00137 if(!_initialized){
00138 _initialize();
00139 }
00140
00141
00142 ros::Time now = ros::Time::now();
00143 ros::Duration timeStep = now - _previousTime;
00144
00145
00146
00147
00148 Eigen::Matrix<simFloat, 3, 1> position;
00149
00150 Eigen::Quaternion< simFloat > orientation;
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
00159
00160
00161 position = nwuToNed*position;
00162 linVelocity = nwuToNed*linVelocity;
00163 angVelocity = orientation.conjugate()*angVelocity;
00164 orientation = nwuToNed*orientation;
00165
00166
00167
00168
00169 if (orientation.w()<0){
00170 orientation.coeffs() *=-1;
00171 }
00172
00173
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
00191
00192 _pub.publish(msg);
00193 }
00194
00195 simFloat TotforceZ = 0.0;
00196
00197 if (_ctrlMode == CustomDataHeaders::DIRECT){
00198
00199
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
00206 TotforceZ =+ -(simFloat)_tkMotorCommands[motorIdx];
00207
00208
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
00220
00221
00222
00223
00224
00225
00226 TotforceZ = (simFloat)_tkCommands.thrust;
00227
00228
00229
00230
00231
00232
00233
00234
00235
00236
00237
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
00246
00247
00248
00249
00250
00251
00252
00253 const double cos_r = cos((double)rpy(0));
00254
00255 const double sin_r = sin((double)rpy(0));
00256
00257 const double cos_p = cos((double)rpy(1));
00258
00259 const double sin_p = sin((double)rpy(1));
00260
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
00273 const simFloat errorRoll = (_tkCommands.roll)-(rpy(0));
00274 const simFloat errorPitch = (_tkCommands.pitch)-(rpy(1));
00275
00276
00277
00278
00279
00280
00281
00282
00283
00284
00285
00286
00287
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
00296 kp_att*(errorRoll) + kd_att*(0-rpyRate(0))+0*0.001*_integralTermRoll,
00297
00298
00299 kp_att*(errorPitch) + kd_att*(0-rpyRate(1))+0*0.002*_integralTermPitch,
00300
00301 _kp_yaw*(_tkCommands.yaw- rpyRate(2)));
00302
00303
00304
00305
00306
00307
00308
00309
00310
00311
00312
00313 rpyTorque = nwuToNed*orientation*rpyTorque;
00314
00315
00316 Eigen::Matrix< simFloat, 3, 1> worldForce = nwuToNed*orientation*Eigen::Matrix< simFloat, 3, 1>(0.0,0.0,(simFloat)_tkCommands.thrust);
00317
00318
00319
00320
00321
00322
00323
00324
00325
00326
00327
00328
00329
00330
00331 if(simAddForceAndTorque(_associatedObjectID, worldForce.data(), rpyTorque.data())==-1){
00332
00333 simSetLastError( _associatedObjectName.c_str(), "Error applying force.");
00334 } else {
00335 for (uint motorIdx = 0; motorIdx < 4; ++motorIdx){
00336
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;
00348
00349
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);
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;
00374
00375
00376
00377
00378
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
00389
00390
00391
00392
00393
00394 }
00395
00396
00397 void Quadrotor_tk_Handler::_initialize(){
00398 if (_initialized)
00399 return;
00400
00401
00402 std::vector<unsigned char> developerCustomData;
00403 getDeveloperCustomData(developerCustomData);
00404
00405
00406 std::vector<unsigned char> tempMainData;
00407 std::stringstream ss;
00408
00409 if (CAccess::extractSerializationData(developerCustomData, CustomDataHeaders::IMU_DATA_MASS,tempMainData)){
00410
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
00445 for(uint motorIdx = 0; motorIdx < 4; ++motorIdx){
00446 _handleOfJoint[motorIdx] = -1;
00447 }
00448 std::vector<int> toExplore;
00449 toExplore.push_back(_associatedObjectID);
00450 while (toExplore.size()!=0)
00451 {
00452 int objHandle=toExplore[toExplore.size()-1];
00453 toExplore.pop_back();
00454
00455 int index=0;
00456 int childHandle=simGetObjectChild(objHandle,index++);
00457 while (childHandle!=-1) {
00458 toExplore.push_back(childHandle);
00459
00460 childHandle=simGetObjectChild(objHandle,index++);
00461 }
00462
00463
00464 int buffSize=simGetObjectCustomDataLength(objHandle,CustomDataHeaders::DEVELOPER_DATA_HEADER);
00465 if (buffSize!=0) {
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
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;
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;
00484 ss << "- [" << _associatedObjectName << "] Found CENTER OF MASS in '"<< simGetObjectName(objHandle) <<"'." << std::endl;
00485 }
00486 }
00487 }
00488
00489
00490
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
00512 _sub = _nh.subscribe(rosTopicCommands, 1000, &Quadrotor_tk_Handler::tkCommandsCallback, this);
00513
00514
00515
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
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