diff --git a/Gazebo_Distributed_MPI/gazebo/physics/World.cc b/Gazebo_Distributed_MPI/gazebo/physics/World.cc index 238c2b9..a00d6ba 100644 --- a/Gazebo_Distributed_MPI/gazebo/physics/World.cc +++ b/Gazebo_Distributed_MPI/gazebo/physics/World.cc @@ -106,6 +106,7 @@ double before_updatePhysicsTime = 0; // little double updatePhysicsTime = 0; double before_mpiTime = 0; double barrierTime = 0; +double waitTime = 0; double mpiTime = 0; double after_mpiTime = 0; double wholeUpdataTime = 0; @@ -119,6 +120,7 @@ double before_updatePhysicsTime2 = 0; double updatePhysicsTime2 = 0; double before_mpiTime2 = 0; double barrierTime2 = 0; +double waitTime2 = 0; double mpiTime2 = 0; double after_mpiTime2 = 0; double wholeUpdataTime2 = 0; @@ -851,73 +853,76 @@ void World::Update() DIAG_TIMER_LAP("World::Update", "Events::worldUpdateBegin"); - // // Added by zhangshuai 2019.10.24 for non-block MPI communication----Begin - // if (1 == this->flag && this->mpi_flag == true) - // { + // Added by zhangshuai 2019.10.24 for non-block MPI communication----Begin + if (1 == this->flag && this->mpi_flag == true) + { - // // Added by zhangshuai 2019.04.03 for count time ----Begin - // #ifdef USE_COUNT_TIME - // gettimeofday(&tv, NULL); - // cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; - // #endif + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; +#endif - // // MPI_Barrier(MPI_COMM_WORLD); + MPI_Barrier(MPI_COMM_WORLD); - // // MPI_Wait(&request, &status); + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + barrierTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; +#endif - // int test_flag; - // MPI_Test(&request, &test_flag, &status); - // while (test_flag == false) - // { - // std::cout << "MPI_Test flag : false" << std::endl; - // MPI_Test(&request, &test_flag, &status); - // } + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; +#endif - // // Added by zhangshuai 2019.04.03 for count time ----Begin - // #ifdef USE_COUNT_TIME - // gettimeofday(&tv, NULL); - // barrierTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; - // #endif + MPI_Wait(&request, &status); + // MPI_Wait(&request, MPI_STATUS_IGNORE); - // // MPI_Barrier(MPI_COMM_WORLD); + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + waitTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; +#endif - // // Added by zhangshuai 2019.04.03 for count time ----Begin - // #ifdef USE_COUNT_TIME - // gettimeofday(&tv, NULL); - // cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; - // #endif - // // Added by zhangshuai 2019.04.03 for count time ----End + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End - // //receive and get information from other processes - // int tmp_gazebo_count = this->distribution->GetGazeboCount(); - // for (int tmp_gazebo_id = 0; tmp_gazebo_id < tmp_gazebo_count; tmp_gazebo_id++) - // { - // if (this->gazeboLocalID != tmp_gazebo_id) - // { - // unsigned int tmp_model_count = this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelCount(); - // CommunicationData *tmpBufferData = new CommunicationData[tmp_model_count]; + //receive and get information from other processes + int tmp_gazebo_count = this->distribution->GetGazeboCount(); + for (int tmp_gazebo_id = 0; tmp_gazebo_id < tmp_gazebo_count; tmp_gazebo_id++) + { + if (this->gazeboLocalID != tmp_gazebo_id) + { + unsigned int tmp_model_count = this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelCount(); + CommunicationData *tmpBufferData = new CommunicationData[tmp_model_count]; - // memcpy(tmpBufferData, (receiveBuffer + this->displs[tmp_gazebo_id]), this->bufferLen[tmp_gazebo_id]); + memcpy(tmpBufferData, (receiveBuffer + this->displs[tmp_gazebo_id]), this->bufferLen[tmp_gazebo_id]); - // for (unsigned int i = 0; i < tmp_model_count; i++) - // { - // // this->GetModel(tmp_model_name)->GetLink("canonical")->SetWorldPose(tmpBufferData[i].model_pose); // reserve + for (unsigned int i = 0; i < tmp_model_count; i++) + { + // this->GetModel(tmp_model_name)->GetLink("canonical")->SetWorldPose(tmpBufferData[i].model_pose); // reserve - // // this->GetModelById(this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelID(i))->SetWorldPose(tmpBufferData[i].model_pose); - // this->GetModelById(this->worldModelIDs_V[tmp_gazebo_id][i])->SetWorldPose(tmpBufferData[i].model_pose); - // } + // this->GetModelById(this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelID(i))->SetWorldPose(tmpBufferData[i].model_pose); + this->GetModelById(this->worldModelIDs_V[tmp_gazebo_id][i])->SetWorldPose(tmpBufferData[i].model_pose); + } - // delete[] tmpBufferData; - // } - // } - // // Added by zhangshuai 2019.04.03 for count time ----Begin - // #ifdef USE_COUNT_TIME - // gettimeofday(&tv, NULL); - // after_mpiTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; - // #endif - // // Added by zhangshuai 2019.04.03 for count time ----End - // } - // // Added by zhangshuai 2019.10.24 for non-block MPI communication ----End + delete[] tmpBufferData; + } + } + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + after_mpiTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + } + // Added by zhangshuai 2019.10.24 for non-block MPI communication ----End // Added by zhangshuai 2019.04.03 for count time ----Begin #ifdef USE_COUNT_TIME @@ -1099,8 +1104,6 @@ void World::Update() MPI_Iallgatherv(this->sendBuffer, this->sendBufferLen, MPI_CHAR, this->receiveBuffer, this->bufferLen, this->displs, MPI_CHAR, MPI_COMM_WORLD, &request); // MPI_Allgatherv(this->sendBuffer, this->sendBufferLen, MPI_CHAR, this->receiveBuffer, this->bufferLen, this->displs, MPI_CHAR, MPI_COMM_WORLD); - // MPI_Barrier(MPI_COMM_WORLD); - // Added by zhangshuai 2019.04.03 for count time ----Begin #ifdef USE_COUNT_TIME gettimeofday(&tv, NULL); @@ -1108,71 +1111,72 @@ void World::Update() #endif // Added by zhangshuai 2019.04.03 for count time ----End - // this->mpi_flag = true; + this->mpi_flag = true; - gazebo::common::Time::NSleep(200000); + // // Added by zhangshuai 2019.04.03 for count time ----Begin + // #ifdef USE_COUNT_TIME + // gettimeofday(&tv, NULL); + // cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; + // #endif - // Added by zhangshuai 2019.04.03 for count time ----Begin -#ifdef USE_COUNT_TIME - gettimeofday(&tv, NULL); - cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; -#endif + // MPI_Barrier(MPI_COMM_WORLD); - // MPI_Barrier(MPI_COMM_WORLD); + // // Added by zhangshuai 2019.04.03 for count time ----Begin + // #ifdef USE_COUNT_TIME + // gettimeofday(&tv, NULL); + // barrierTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; + // #endif - MPI_Wait(&request, &status); + // // Added by zhangshuai 2019.04.03 for count time ----Begin + // #ifdef USE_COUNT_TIME + // gettimeofday(&tv, NULL); + // cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; + // #endif - // int test_flag; - // MPI_Test(&request, &test_flag, &status); - // while (test_flag == false) - // { - // std::cout << "MPI_Test flag : false" << std::endl; - // MPI_Test(&request, &test_flag, &status); - // } + // MPI_Wait(&request, &status); + // // MPI_Wait(&request, MPI_STATUS_IGNORE); - // Added by zhangshuai 2019.04.03 for count time ----Begin -#ifdef USE_COUNT_TIME - gettimeofday(&tv, NULL); - barrierTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; -#endif + // // Added by zhangshuai 2019.04.03 for count time ----Begin + // #ifdef USE_COUNT_TIME + // gettimeofday(&tv, NULL); + // waitTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; + // #endif - // MPI_Barrier(MPI_COMM_WORLD); + // // Added by zhangshuai 2019.04.03 for count time ----Begin + // #ifdef USE_COUNT_TIME + // gettimeofday(&tv, NULL); + // cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; + // #endif + // // Added by zhangshuai 2019.04.03 for count time ----End - // Added by zhangshuai 2019.04.03 for count time ----Begin -#ifdef USE_COUNT_TIME - gettimeofday(&tv, NULL); - cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; -#endif - // Added by zhangshuai 2019.04.03 for count time ----End + // //receive and get information from other processes + // int tmp_gazebo_count = this->distribution->GetGazeboCount(); + // for (int tmp_gazebo_id = 0; tmp_gazebo_id < tmp_gazebo_count; tmp_gazebo_id++) + // { + // if (this->gazeboLocalID != tmp_gazebo_id) + // { + // unsigned int tmp_model_count = this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelCount(); + // CommunicationData *tmpBufferData = new CommunicationData[tmp_model_count]; - //receive and get information from other processes - int tmp_gazebo_count = this->distribution->GetGazeboCount(); - for (int tmp_gazebo_id = 0; tmp_gazebo_id < tmp_gazebo_count; tmp_gazebo_id++) - { - if (this->gazeboLocalID != tmp_gazebo_id) - { - unsigned int tmp_model_count = this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelCount(); - CommunicationData *tmpBufferData = new CommunicationData[tmp_model_count]; + // memcpy(tmpBufferData, (receiveBuffer + this->displs[tmp_gazebo_id]), this->bufferLen[tmp_gazebo_id]); - memcpy(tmpBufferData, (receiveBuffer + this->displs[tmp_gazebo_id]), this->bufferLen[tmp_gazebo_id]); + // for (unsigned int i = 0; i < tmp_model_count; i++) + // { + // // this->GetModel(tmp_model_name)->GetLink("canonical")->SetWorldPose(tmpBufferData[i].model_pose); // reserve - for (unsigned int i = 0; i < tmp_model_count; i++) - { - // this->GetModel(tmp_model_name)->GetLink("canonical")->SetWorldPose(tmpBufferData[i].model_pose); // reserve + // // this->GetModelById(this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelID(i))->SetWorldPose(tmpBufferData[i].model_pose); + // this->GetModelById(this->worldModelIDs_V[tmp_gazebo_id][i])->SetWorldPose(tmpBufferData[i].model_pose); + // } - // this->GetModelById(this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelID(i))->SetWorldPose(tmpBufferData[i].model_pose); - this->GetModelById(this->worldModelIDs_V[tmp_gazebo_id][i])->SetWorldPose(tmpBufferData[i].model_pose); - } - - delete[] tmpBufferData; - } - } - // Added by zhangshuai 2019.04.03 for count time ----Begin -#ifdef USE_COUNT_TIME - gettimeofday(&tv, NULL); - after_mpiTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; -#endif - // Added by zhangshuai 2019.04.03 for count time ----End + // delete[] tmpBufferData; + // } + // } + // // Added by zhangshuai 2019.04.03 for count time ----Begin + // #ifdef USE_COUNT_TIME + // gettimeofday(&tv, NULL); + // after_mpiTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; + // #endif + // // Added by zhangshuai 2019.04.03 for count time ----End } // Added by zhangshuai 2019.04.23 for MPI communication ----End @@ -1208,6 +1212,7 @@ void World::Update() updatePhysicsTime2 = updatePhysicsTime; before_mpiTime2 = before_mpiTime; barrierTime2 = barrierTime; + waitTime2 = waitTime; mpiTime2 = mpiTime; after_mpiTime2 = after_mpiTime; wholeUpdataTime2 = wholeUpdataTime; @@ -1227,6 +1232,7 @@ void World::Update() double ave_updateCollisionTime = (updateCollisionTime - updateCollisionTime2) * 1000.0 / (this->dataPtr->iterations - start_iterations); double ave_updatePhysicsTime = (updatePhysicsTime - updatePhysicsTime2) * 1000.0 / (this->dataPtr->iterations - start_iterations); double ave_barrierTime = (barrierTime - barrierTime2) * 1000.0 / (this->dataPtr->iterations - start_iterations); + double ave_waitTime = (waitTime - waitTime2) * 1000.0 / (this->dataPtr->iterations - start_iterations); double ave_before_mpiTime = (before_mpiTime - before_mpiTime2) * 1000.0 / (this->dataPtr->iterations - start_iterations); double ave_mpiTime = (mpiTime - mpiTime2) * 1000.0 / (this->dataPtr->iterations - start_iterations); double ave_after_mpiTime = (after_mpiTime - after_mpiTime2) * 1000.0 / (this->dataPtr->iterations - start_iterations); @@ -1237,6 +1243,7 @@ void World::Update() double perce_updateCollisionTime = (ave_updateCollisionTime / ave_wholeStepTime) * 100; double perce_updatePhysicsTime = (ave_updatePhysicsTime / ave_wholeStepTime) * 100; double perce_barrierTime = (ave_barrierTime / ave_wholeStepTime) * 100; + double perce_waitTime = (ave_waitTime / ave_wholeStepTime) * 100; double perce_wholeMpiTime = (ave_wholeMpiTime / ave_wholeStepTime) * 100; double perce_othersTime = (ave_othersTime / ave_wholeStepTime) * 100; @@ -1250,36 +1257,31 @@ void World::Update() std::cout << "***************************************************************************" << std::endl; std::cout << "===== average worldUpdateBeginTime:\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_worldUpdateBeginTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << perce_worldUpdateBeginTime << "%)" << "\tms =====\t" << this->gazeboLocalID << std::endl; - std::cout << "===== average updateCollisionTime:\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_updateCollisionTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << perce_updateCollisionTime << "%)" + std::cout << "===== average updateCollisionTime :\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_updateCollisionTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << perce_updateCollisionTime << "%)" << "\tms =====\t" << this->gazeboLocalID << std::endl; - std::cout << "===== average updatePhysicsTime:\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_updatePhysicsTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << perce_updatePhysicsTime << "%)" + std::cout << "===== average updatePhysicsTime :\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_updatePhysicsTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << perce_updatePhysicsTime << "%)" << "\tms =====\t" << this->gazeboLocalID << std::endl; - std::cout << "===== average barrierTime:\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_barrierTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << perce_barrierTime << "%)" + std::cout << "===== average barrierTime :\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_barrierTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << perce_barrierTime << "%)" << "\tms =====\t" << this->gazeboLocalID << std::endl; - std::cout << "===== average wholeMpiTime:\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_wholeMpiTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << perce_wholeMpiTime << "%)" + std::cout << "===== average waitTime :\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_waitTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << perce_waitTime << "%)" << "\tms =====\t" << this->gazeboLocalID << std::endl; - std::cout << "===== average othersTime:\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_othersTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << perce_othersTime << "%)" + std::cout << "===== average wholeMpiTime :\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_wholeMpiTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << perce_wholeMpiTime << "%)" << "\tms =====\t" << this->gazeboLocalID << std::endl; - std::cout << "===== average wholeStepTime:\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_wholeStepTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << 100.0 << "%)" + std::cout << "===== average othersTime :\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_othersTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << perce_othersTime << "%)" << "\tms =====\t" << this->gazeboLocalID << std::endl; - std::cout << "===== average RTF:\t" << std::setiosflags(std::ios::fixed) << std::setprecision(3) << ave_RTF << "\t =====\t" << this->gazeboLocalID << std::endl; + std::cout << "===== average wholeStepTime :\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_wholeStepTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << 100.0 << "%)" + << "\tms =====\t" << this->gazeboLocalID << std::endl; + std::cout << "===== average RTF :\t" << std::setiosflags(std::ios::fixed) << std::setprecision(3) << ave_RTF << "\t =====\t" << this->gazeboLocalID << std::endl; std::cout << "---------------------------------------------------------------------------" << std::endl; - std::cout << "===== average before_mpiTime:\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_before_mpiTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << perce_before_mpiTime << "%)" + std::cout << "===== average before_mpiTime :\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_before_mpiTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << perce_before_mpiTime << "%)" << "\tms =====\t" << this->gazeboLocalID << std::endl; - std::cout << "===== average mpiTime:\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_mpiTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << perce_mpiTime << "%)" + std::cout << "===== average mpiTime :\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_mpiTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << perce_mpiTime << "%)" << "\tms =====\t" << this->gazeboLocalID << std::endl; - std::cout << "===== average after_mpiTime:\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_after_mpiTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << perce_after_mpiTime << "%)" + std::cout << "===== average after_mpiTime :\t" << std::setiosflags(std::ios::fixed) << std::setprecision(4) << ave_after_mpiTime << " (" << std::setiosflags(std::ios::fixed) << std::setprecision(2) << perce_after_mpiTime << "%)" << "\tms =====\t" << this->gazeboLocalID << std::endl; std::cout << "***************************************************************************" << std::endl; - // std::cout << "===== average before_worldUpdateBeginTime:\t" << (before_worldUpdateBeginTime - before_worldUpdateBeginTime2) * 1000.0 / (this->dataPtr->iterations - start_iterations) << "\tms =====\t" << this->gazeboLocalID << std::endl; - // std::cout << "===== average modelUpdateFuncTime:\t" << (modelUpdateFuncTime - modelUpdateFuncTime2) * 1000.0 / (this->dataPtr->iterations - start_iterations) << "\tms =====\t" << this->gazeboLocalID << std::endl; - // std::cout << "===== average loggingTime:\t" << (loggingTime - loggingTime2) * 1000.0 / (this->dataPtr->iterations - start_iterations) << "\tms =====\t" << this->gazeboLocalID << std::endl; - // std::cout << "===== average before_updatePhysicsTime:\t" << (before_updatePhysicsTime - before_updatePhysicsTime2) * 1000.0 / (this->dataPtr->iterations - start_iterations) << "\tms =====\t" << this->gazeboLocalID << std::endl; - // double wholeAddTime = before_worldUpdateBeginTime + worldUpdateBeginTime + modelUpdateFuncTime + updateCollisionTime + loggingTime + before_updatePhysicsTime + updatePhysicsTime + before_mpiTime + mpiTime + after_mpiTime - (before_worldUpdateBeginTime2 + worldUpdateBeginTime2 + modelUpdateFuncTime2 + updateCollisionTime2 + loggingTime2 + before_updatePhysicsTime2 + updatePhysicsTime2 + before_mpiTime2 + mpiTime2 + after_mpiTime2); - // std::cout << "===== average wholeAddTime:\t" << wholeAddTime * 1000.0 / (this->dataPtr->iterations - start_iterations) << "\tms =====\t" << this->gazeboLocalID << std::endl; - // } // // test for worldModelIDs_V Begin 2019.10.24 diff --git a/Gazebo_Distributed_MPI/mpi_run/MPI_Gazebo_pause.sh b/Gazebo_Distributed_MPI/mpi_run/MPI_Gazebo_pause.sh new file mode 100755 index 0000000..7233ae4 --- /dev/null +++ b/Gazebo_Distributed_MPI/mpi_run/MPI_Gazebo_pause.sh @@ -0,0 +1,12 @@ +#!/bin/bash +################################################################################################################################################### +# Author: Zhang Shuai # +# Date: 2019-10-29 # +################################################################################################################################################### + +export GAZEBO_MASTER_URI=http://localhost:11345 +gz world -p 1 +export GAZEBO_MASTER_URI=http://localhost:11346 +gz world -p 1 + +exit 0 diff --git a/Gazebo_Distributed_MPI/mpi_run/MPI_Gazebo_start.sh b/Gazebo_Distributed_MPI/mpi_run/MPI_Gazebo_start.sh new file mode 100755 index 0000000..970c1b3 --- /dev/null +++ b/Gazebo_Distributed_MPI/mpi_run/MPI_Gazebo_start.sh @@ -0,0 +1,12 @@ +#!/bin/bash +################################################################################################################################################### +# Author: Zhang Shuai # +# Date: 2019-10-29 # +################################################################################################################################################### + +export GAZEBO_MASTER_URI=http://localhost:11345 +gz world -p 0 +export GAZEBO_MASTER_URI=http://localhost:11346 +gz world -p 0 + +exit 0 diff --git a/Gazebo_Distributed_MPI/mpi_run/hostfile b/Gazebo_Distributed_MPI/mpi_run/hostfile index 2c2a9fe..7ff788c 100644 --- a/Gazebo_Distributed_MPI/mpi_run/hostfile +++ b/Gazebo_Distributed_MPI/mpi_run/hostfile @@ -1,3 +1,3 @@ -airc05-Precision-7920-Tower slots=1 -airc02-PowerEdge-T640 slots=1 +airc05-Precision-7920-Tower slots=2 +#airc02-PowerEdge-T640 slots=1 #airc03-PowerEdge-T640 slots=1 diff --git a/Gazebo_Distributed_MPI/mpi_run/rankfile b/Gazebo_Distributed_MPI/mpi_run/rankfile index d43d3f9..8bc71d6 100755 --- a/Gazebo_Distributed_MPI/mpi_run/rankfile +++ b/Gazebo_Distributed_MPI/mpi_run/rankfile @@ -1,2 +1,2 @@ -rank 0=airc05-Precision-7920-Tower slot=0 -rank 1=airc02-PowerEdge-T640 slot=0 +rank 0=airc05-Precision-7920-Tower slot=0-3 +rank 1=airc05-Precision-7920-Tower slot=20-23 diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/hector_32_single_gazebo_mpi_spawn_test_xxx.launch b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/hector_32_single_gazebo_mpi_spawn_test_xxx.launch new file mode 100644 index 0000000..48361d5 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/hector_32_single_gazebo_mpi_spawn_test_xxx.launch @@ -0,0 +1,360 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/hector_32_single_gazebo_mpi_spawn_test_yyy.launch b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/hector_32_single_gazebo_mpi_spawn_test_yyy.launch new file mode 100644 index 0000000..ed13a98 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/hector_32_single_gazebo_mpi_spawn_test_yyy.launch @@ -0,0 +1,360 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/kunming_airport_distribution_32hector_mpi_test.world b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/kunming_airport_distribution_32hector_mpi_test.world new file mode 100644 index 0000000..386c4dd --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/kunming_airport_distribution_32hector_mpi_test.world @@ -0,0 +1,324 @@ + + + + + + model://sun + + + + model://kunming_airport + 0 0 0 0 0 0 + + + + 0.68 0.68 0.68 1.0 + + + + 0 + + + + + + + + bebop_0 + bebop_1 + bebop_2 + bebop_3 + bebop_4 + bebop_5 + bebop_6 + bebop_7 + bebop_8 + bebop_9 + bebop_10 + bebop_11 + bebop_12 + bebop_13 + bebop_14 + bebop_15 + bebop_16 + bebop_17 + bebop_18 + bebop_19 + bebop_20 + bebop_21 + bebop_22 + bebop_23 + bebop_24 + bebop_25 + bebop_26 + bebop_27 + bebop_28 + bebop_29 + + + bebop_30 + bebop_31 + + + + + 0 + 0.001 + 0 + + + + + + 0 + + + + + + + +