1. MPI_Allgatherv, version 0.6.2

2. add test worlds and for single machine two Gazebo
3. add openmpi version in world.cc
This commit is contained in:
zhangshuai 2019-10-22 11:05:42 +08:00
parent 37dc593069
commit 14053caad7
5 changed files with 2233 additions and 8 deletions

View File

@ -1,4 +1,6 @@
find_package(MPI REQUIRED) # Added by zhangshuai 2019.04.22 for MPI
#find_package(MPI REQUIRED) # Added by zhangshuai 2019.04.22 for MPI
message(STATUS "++++++++++ Using MPI_INCLUDE_PATH: ${MPI_INCLUDE_PATH} ++++++++++") # Added by zhangshuai 2019.04.22 for MPI
include_directories(SYSTEM
${OPENGL_INCLUDE_DIR}

View File

@ -297,11 +297,16 @@ void World::Load(sdf::ElementPtr _sdf)
{
sdf::ElementPtr distributionElem = this->dataPtr->sdf->GetElement("distribution");
char proc_name[MPI_MAX_PROCESSOR_NAME];
char version[MPI_MAX_LIBRARY_VERSION_STRING];
int nameLength;
int versionLength;
MPI_Comm_rank(MPI_COMM_WORLD, &this->gazeboLocalID);
MPI_Comm_size(MPI_COMM_WORLD, &this->nproc);
MPI_Get_processor_name(proc_name, &nameLength);
printf("Gazebo, Iam host %s with rank %d of %d\n", proc_name, this->gazeboLocalID, this->nproc);
MPI_Get_library_version(version, &versionLength);
// printf("Gazebo, I am host %s with rank %d of %d\n", proc_name, this->gazeboLocalID, this->nproc);
std::cout << "Gazebo! I am host " << proc_name << " with rank " << this->gazeboLocalID << " of " << this->nproc
<< "(" << version << ", " << versionLength << ")" << std::endl;
this->flag = distributionElem->Get<int>("flag");
@ -988,6 +993,8 @@ void World::Update()
#endif
// Added by zhangshuai 2019.04.03 for count time ----End
MPI_Barrier(MPI_COMM_WORLD);
// Added by zhangshuai 2019.04.03 for count time ----Begin
#ifdef USE_COUNT_TIME
gettimeofday(&tv, NULL);
@ -996,7 +1003,7 @@ void World::Update()
// 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_Barrier(MPI_COMM_WORLD);
// MPI_Barrier(MPI_COMM_WORLD);
// Added by zhangshuai 2019.04.03 for count time ----Begin
#ifdef USE_COUNT_TIME

View File

@ -12,7 +12,7 @@
</joint>
<link name="${name}_link">
<!-- <inertial>
<!--<inertial>
<mass value="0.001" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001" />
@ -43,7 +43,7 @@
<link name="${name}_optical_frame"/>
<gazebo reference="${name}_link">
<!--<sensor type="camera" name="${name}_camera_sensor">
<!-- <sensor type="camera" name="${name}_camera_sensor">
<update_rate>${update_rate}</update_rate>
<camera>
<horizontal_fov>${hfov * M_PI/180.0}</horizontal_fov>
@ -64,8 +64,8 @@
<cameraInfoTopicName>${cam_info_topic}</cameraInfoTopicName>
<frameName>${name}_optical_frame</frameName>
</plugin>
</sensor>-->
<sensor name='back_left_far_sonar_sensor' type='ray'>
</sensor> -->
<!--<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>