From f70992b5374f80fe5520ea9deb3b5409b9b4da53 Mon Sep 17 00:00:00 2001 From: zhangshuai Date: Wed, 23 Oct 2019 11:11:58 +0800 Subject: [PATCH] 1. MPI_Allgatherv, version 0.6.3 2. modify allgatherv buffer in world.hh 3. CMakeList.txt use SET() to ensure the path of OpenMPI 4.0.1 --- Gazebo_Distributed_MPI/gazebo/CMakeLists.txt | 3 ++ .../gazebo/physics/CMakeLists.txt | 5 ++- .../gazebo/physics/World.cc | 36 ++++++++----------- .../gazebo/physics/World.hh | 22 +++++++----- Gazebo_Distributed_MPI/mpi_run/hostfile | 3 +- Gazebo_Distributed_MPI/mpi_run/rankfile | 2 ++ .../urdf/generic_camera.urdf.xacro | 4 +-- 7 files changed, 40 insertions(+), 35 deletions(-) create mode 100755 Gazebo_Distributed_MPI/mpi_run/rankfile diff --git a/Gazebo_Distributed_MPI/gazebo/CMakeLists.txt b/Gazebo_Distributed_MPI/gazebo/CMakeLists.txt index cea45b6..9c38e8f 100644 --- a/Gazebo_Distributed_MPI/gazebo/CMakeLists.txt +++ b/Gazebo_Distributed_MPI/gazebo/CMakeLists.txt @@ -1,5 +1,8 @@ #find_package(MPI REQUIRED) # Added by zhangshuai 2019.04.22 for MPI +SET(MPI_INCLUDE_PATH /usr/local) +#SET(MPI_INCLUDE_PATH /usr/local/lib/openmpi;/usr/local/include/openmpi) # Added by zhangshuai 2019.10.23 for MPI + message(STATUS "++++++++++ Using MPI_INCLUDE_PATH: ${MPI_INCLUDE_PATH} ++++++++++") # Added by zhangshuai 2019.04.22 for MPI include_directories(SYSTEM diff --git a/Gazebo_Distributed_MPI/gazebo/physics/CMakeLists.txt b/Gazebo_Distributed_MPI/gazebo/physics/CMakeLists.txt index 2f5157f..69e6915 100644 --- a/Gazebo_Distributed_MPI/gazebo/physics/CMakeLists.txt +++ b/Gazebo_Distributed_MPI/gazebo/physics/CMakeLists.txt @@ -1,4 +1,7 @@ -find_package(MPI REQUIRED) # Added by zhangshuai 2019.04.22 for MPI +#find_package(MPI REQUIRED) # Added by zhangshuai 2019.04.22 for MPI +#SET(MPI_INCLUDE_PATH /usr/local/lib/openmpi;/usr/local/include/openmpi) # Added by zhangshuai 2019.10.23 for MPI +SET(MPI_INCLUDE_PATH /usr/local) + include (${gazebo_cmake_dir}/GazeboUtils.cmake) link_directories( diff --git a/Gazebo_Distributed_MPI/gazebo/physics/World.cc b/Gazebo_Distributed_MPI/gazebo/physics/World.cc index 5149ef9..a36002c 100644 --- a/Gazebo_Distributed_MPI/gazebo/physics/World.cc +++ b/Gazebo_Distributed_MPI/gazebo/physics/World.cc @@ -335,6 +335,8 @@ void World::Load(sdf::ElementPtr _sdf) this->modelCounts = this->modelCounts + this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelCount(); } // this->receiveBufferLen = sizeof(CommunicationData) * this->modelCounts; + this->bufferLen = new int[tmp_gazebo_count]; // array that its value is the number of data received from each process + this->displs = new int[tmp_gazebo_count]; // array that its value is the offset number of data received from each process } } //Added by zhangshuai based on zenglei 2019.03.19 ----End @@ -954,22 +956,15 @@ void World::Update() #endif // Added by zhangshuai 2019.04.03 for count time ----End - int tmp_gazebo_count = this->distribution->GetGazeboCount(); - - char *sendBuffer; - char *receiveBuffer; - // for MPI_Allgatherv - - int *tmpbufferLen = new int[tmp_gazebo_count]; // array that its value is the number of data received from each process - int *tmpdispls = new int[tmp_gazebo_count]; // array that its value is the offset number of data received from each process + int tmp_gazebo_count = this->distribution->GetGazeboCount(); for (int tmp_gazebo_id = 0; tmp_gazebo_id < tmp_gazebo_count; tmp_gazebo_id++) { - tmpbufferLen[tmp_gazebo_id] = sizeof(CommunicationData) * this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelCount(); + this->bufferLen[tmp_gazebo_id] = sizeof(CommunicationData) * this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelCount(); - tmpdispls[tmp_gazebo_id] = 0; + this->displs[tmp_gazebo_id] = 0; for (int k = 0; k < tmp_gazebo_id; k++) - tmpdispls[tmp_gazebo_id] = tmpdispls[tmp_gazebo_id] + tmpbufferLen[k]; + this->displs[tmp_gazebo_id] = this->displs[tmp_gazebo_id] + this->bufferLen[k]; } /// make the pose data ready @@ -981,10 +976,10 @@ void World::Update() sendBufferData[i].model_pose = this->GetModelById(this->distribution->GetGazeboIDPtr(this->gazeboLocalID)->GetModelID(i))->GetWorldPose(); } - sendBuffer = (char *)sendBufferData; + this->sendBuffer = (char *)sendBufferData; CommunicationData *receiveBufferData = new CommunicationData[this->modelCounts]; - receiveBuffer = (char *)receiveBufferData; + this->receiveBuffer = (char *)receiveBufferData; // Added by zhangshuai 2019.04.03 for count time ----Begin #ifdef USE_COUNT_TIME @@ -1002,7 +997,9 @@ void World::Update() #endif // Added by zhangshuai 2019.04.03 for count time ----End - MPI_Allgatherv(sendBuffer, this->sendBufferLen, MPI_CHAR, receiveBuffer, tmpbufferLen, tmpdispls, MPI_CHAR, MPI_COMM_WORLD); + // MPI_Iallgatherv(this->sendBuffer, this->sendBufferLen, MPI_CHAR, this->receiveBuffer, this->bufferLen, this->displs, MPI_CHAR, MPI_COMM_WORLD, this->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 @@ -1027,7 +1024,7 @@ void World::Update() unsigned int tmp_model_count = this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelCount(); CommunicationData *tmpBufferData = new CommunicationData[tmp_model_count]; - memcpy(tmpBufferData, (receiveBuffer + tmpdispls[tmp_gazebo_id]), tmpbufferLen[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++) { @@ -1040,8 +1037,6 @@ void World::Update() delete[] sendBufferData; delete[] receiveBufferData; - delete[] tmpbufferLen; - delete[] tmpdispls; // Added by zhangshuai 2019.04.03 for count time ----Begin #ifdef USE_COUNT_TIME @@ -1049,10 +1044,7 @@ void World::Update() 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 - - // MPI_Barrier(MPI_COMM_WORLD); } - // MPI_Barrier(MPI_COMM_WORLD); // Added by zhangshuai 2019.04.23 for MPI communication ----End // Only update state information if logging data. @@ -1236,8 +1228,8 @@ void World::Fini() } //Added by zhangshuai 2019.06.10 ----Begin - // delete[] this->bufferLen; - // delete[] this->displs; + delete[] this->bufferLen; + delete[] this->displs; //Added by zhangshuai 2019.06.10 ----End } diff --git a/Gazebo_Distributed_MPI/gazebo/physics/World.hh b/Gazebo_Distributed_MPI/gazebo/physics/World.hh index 13e03f1..17d8611 100644 --- a/Gazebo_Distributed_MPI/gazebo/physics/World.hh +++ b/Gazebo_Distributed_MPI/gazebo/physics/World.hh @@ -56,6 +56,8 @@ #include "gazebo/physics/Distribution.hh" // Added by zhangshuai 2019.04.01 ----End +// #include // Added by zhangshuai 2019.10.22 for MPI + namespace gazebo { namespace physics @@ -758,23 +760,26 @@ private: private: int *displs; + /// \brief the . +private: + char *sendBuffer; // Added by zhangshuai 2019.10.22 for MPI_Iallgather + /// \brief the . +private: + char *receiveBuffer; // Added by zhangshuai 2019.10.22 for MPI_Iallgather + /// \brief the . private: int modelCounts; +// /// \brief the . +// private: +// MPI_Request *request; // Added by zhangshuai 2019.10.22 for MPI_Iallgather + // /// \brief the . // private: // // Distribution_V distributions; // std::vector distribution; - // public: - // DistributionPtr GetDistribution(); - - // public: - // int GetGazeboLocalID(); - - // public: - // int GetFlag(); // Added by zhangshuai 2019.06.10 ----End // Added by zhangshuai for MPI 2019.07.11 ----Begin @@ -791,7 +796,6 @@ public: public: ModelPtr GetOwnModel(unsigned int _index) const; // Added by zhangshuai for MPI 2019.07.11 ----End - }; /// \} } // namespace physics diff --git a/Gazebo_Distributed_MPI/mpi_run/hostfile b/Gazebo_Distributed_MPI/mpi_run/hostfile index 76e0e52..2c2a9fe 100644 --- a/Gazebo_Distributed_MPI/mpi_run/hostfile +++ b/Gazebo_Distributed_MPI/mpi_run/hostfile @@ -1,2 +1,3 @@ +airc05-Precision-7920-Tower slots=1 airc02-PowerEdge-T640 slots=1 -airc03-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 new file mode 100755 index 0000000..d43d3f9 --- /dev/null +++ b/Gazebo_Distributed_MPI/mpi_run/rankfile @@ -0,0 +1,2 @@ +rank 0=airc05-Precision-7920-Tower slot=0 +rank 1=airc02-PowerEdge-T640 slot=0 diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/generic_camera.urdf.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/generic_camera.urdf.xacro index e51503e..d19bd1c 100644 --- a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/generic_camera.urdf.xacro +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/generic_camera.urdf.xacro @@ -65,7 +65,7 @@ ${name}_optical_frame --> - +