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
This commit is contained in:
zhangshuai 2019-10-23 11:11:58 +08:00
parent 14053caad7
commit f70992b537
7 changed files with 40 additions and 35 deletions

View File

@ -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

View File

@ -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(

View File

@ -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
}

View File

@ -56,6 +56,8 @@
#include "gazebo/physics/Distribution.hh"
// Added by zhangshuai 2019.04.01 ----End
// #include <mpi.h> // 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<CommunicationData> 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

View File

@ -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

View File

@ -0,0 +1,2 @@
rank 0=airc05-Precision-7920-Tower slot=0
rank 1=airc02-PowerEdge-T640 slot=0

View File

@ -65,7 +65,7 @@
<frameName>${name}_optical_frame</frameName>
</plugin>
</sensor> -->
<!--<sensor name='back_left_far_sonar_sensor' type='ray'>
<sensor name='back_left_far_sonar_sensor' type='ray'>
<ray>
<scan>
<horizontal>
@ -89,7 +89,7 @@
<always_on>0</always_on>
<update_rate>5</update_rate>
<pose frame=''>0.7 2.4 0.5 0 -0 1.5707</pose>
</sensor>-->
</sensor>
</gazebo>
</xacro:macro>