1. MPI_Allgatherv, version 0.5.1

2. inorder to modify "modelupdatefunc" module, add "models" list in GazeboID.cc & .hh, when load model in world.cc, modelprt will be pushback to this list
This commit is contained in:
zhangshuai 2019-07-10 21:35:15 +08:00
parent 6bf9cf2bb2
commit 8c093b02be
3 changed files with 108 additions and 14 deletions

View File

@ -40,7 +40,7 @@
// #include "gazebo/common/Plugin.hh" // #include "gazebo/common/Plugin.hh"
// #include "gazebo/common/Events.hh" // #include "gazebo/common/Events.hh"
// #include "gazebo/common/Exception.hh" // #include "gazebo/common/Exception.hh"
// #include "gazebo/common/Console.hh" #include "gazebo/common/Console.hh"
// #include "gazebo/common/CommonTypes.hh" // #include "gazebo/common/CommonTypes.hh"
// #include "gazebo/physics/Gripper.hh" // #include "gazebo/physics/Gripper.hh"
@ -85,7 +85,7 @@ void GazeboID::Load(sdf::ElementPtr _sdf)
while (modelNameElem) while (modelNameElem)
{ {
modelNames.push_back(modelNameElem->Get<std::string>()); modelNames.push_back(modelNameElem->Get<std::string>());
modelIDs.push_back(0); //initial state is 0 modelIDs.push_back(0); //initial state is 0
modelNameElem = modelNameElem->GetNextElement("model_name"); modelNameElem = modelNameElem->GetNextElement("model_name");
} }
} }
@ -126,4 +126,17 @@ void GazeboID::Fini()
{ {
this->modelNames.clear(); this->modelNames.clear();
this->sdf.reset(); this->sdf.reset();
}
//////////////////////////////////////////////////
ModelPtr GazeboID::GetModel(unsigned int _index) const
{
if (_index >= this->models.size())
{
gzerr << "Given model index[" << _index << "] is out of range[0.."
<< this->models.size() << "]\n";
return ModelPtr();
}
return this->models[_index];
} }

View File

@ -40,8 +40,8 @@ namespace gazebo
{ {
namespace physics namespace physics
{ {
/// \class Distribution Distribution.hh physics/physics.hh /// \class GazeboID GazeboID.hh physics/physics.hh
/// \brief Distribution is used to store information about the distributed simulation. /// \brief GazeboID is used to store information about the distributed simulation.
class GZ_PHYSICS_VISIBLE GazeboID class GZ_PHYSICS_VISIBLE GazeboID
{ {
/// \brief Constructor. /// \brief Constructor.
@ -53,7 +53,7 @@ public:
public: public:
virtual ~GazeboID(); virtual ~GazeboID();
/// \brief Load the Distribution. /// \brief Load the GazeboID.
/// \param[in] _sdf SDF parameters to load from. /// \param[in] _sdf SDF parameters to load from.
public: public:
void Load(sdf::ElementPtr _sdf); void Load(sdf::ElementPtr _sdf);
@ -63,8 +63,8 @@ public:
public: public:
int GetGazeboID(); int GetGazeboID();
/// \brief Get the number of models this Distribution has. /// \brief Get the number of models this GazeboID has.
/// \return Number of models associated with this Distribution. /// \return Number of models associated with this GazeboID.
public: public:
unsigned int GetModelCount(); unsigned int GetModelCount();
@ -89,6 +89,14 @@ public:
/// \brief Finialize the gazeboID /// \brief Finialize the gazeboID
public: public:
void Fini(); void Fini();
/// \brief Get a model based on an index.
/// Get a Model using an index, where index must be greater than zero
/// and less than GazeboID::GetModelCount()
/// \param[in] _index The index of the model [0..GetModelCount)
/// \return A pointer to the Model. NULL if _index is invalid.
public:
ModelPtr GetModel(unsigned int _index) const;
/// \brief The Distribution's current SDF description. /// \brief The Distribution's current SDF description.
private: private:
@ -105,6 +113,10 @@ private:
/// \brief Models ID in this gazebo /// \brief Models ID in this gazebo
private: private:
std::vector<unsigned int> modelIDs; std::vector<unsigned int> modelIDs;
/// \brief A cached list of models. This is here for performance.
public:
Model_V models;
}; };
} // namespace physics } // namespace physics

View File

@ -1817,8 +1817,39 @@ void World::BuildSceneMsg(msgs::Scene &_scene, BasePtr _entity)
void World::ModelUpdateSingleLoop() void World::ModelUpdateSingleLoop()
{ {
// Update all the models // Update all the models
for (unsigned int i = 0; i < this->dataPtr->rootElement->GetChildCount(); i++) /// original part
this->dataPtr->rootElement->GetChild(i)->Update(); //for (unsigned int i = 0; i < this->dataPtr->rootElement->GetChildCount(); i++)
// this->dataPtr->rootElement->GetChild(i)->Update();
/// original part
// test by zhangshuai 2019.07.09 ----Begin
// for (unsigned int i = 0; i < this->dataPtr->rootElement->GetChildCount(); i++)
// {
// this->dataPtr->rootElement->GetChild(i)->Update();
// std::cout << "GetChildCount() : " << this->dataPtr->rootElement->GetChildCount() << std::endl; //zhangshuai test 2019.07.09
// std::cout << "GetChild(" << i << ") : " << this->dataPtr->rootElement->GetChild(i)->GetName() << std::endl;
// std::cout << "rootElement->GetName() : " << this->dataPtr->rootElement->GetName() << std::endl;
// std::cout << "this->GetModelCount() : " << this->GetModelCount() << std::endl;
// }
// test by zhangshuai 2019.07.09 ----End
// test by zhangshuai 2019.07.10 ----Begin
// for (unsigned int i = 0; i < this->GetModelCount(); i++)
// {
// this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModel(i)->Update();
// this->GetModel(i)->Update();
// std::cout << "this->GetModelCount() : " << this->GetModelCount() << std::endl;
// std::cout << "this->GetModel(i)->GetName() : " << this->GetModel(i)->GetName() << std::endl;
// }
// test by zhangshuai 2019.07.10 ----End
for (unsigned int i = 0; i < this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModelCount(); i++)
{
this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModel(i)->Update();
// this->GetModel(i)->Update();
std::cout << "GetModelCount() : " << this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModelCount() << std::endl;
std::cout << "GetModel(i)->GetName() : " << this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModel(i)->GetName() << std::endl;
}
} }
////////////////////////////////////////////////// //////////////////////////////////////////////////
@ -1842,17 +1873,52 @@ void World::LoadPlugins()
{ {
ModelPtr model = boost::static_pointer_cast<Model>( ModelPtr model = boost::static_pointer_cast<Model>(
this->dataPtr->rootElement->GetChild(i)); this->dataPtr->rootElement->GetChild(i));
// Modified by zhangshuai 2019.04.02 ----Begin // Modified by zhangshuai 2019.04.02 ----Begin
if (this->flag == 1) if (this->flag == 1)
{ {
// Judge if the model to load is simulated in this gazebo // Judge if the model to load is simulated in this gazebo
for (unsigned int j = 0; j < this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModelCount(); j++)
// for (unsigned int i = 0; i < this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModelCount(); i++)
// {
// if (model->GetName() == this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModelName(i))
// {
// // Original part
// model->LoadPlugins();
// // Original part
// this->distribution->GetGazeboIDPtr(gazeboLocalID)->SetModelID(i, model->GetId());
// }
// }
int tmp_gazebo_count = this->distribution->GetGazeboCount();
for (int tmp_gazebo_id = 0; tmp_gazebo_id < tmp_gazebo_count; tmp_gazebo_id++)
{ {
if (model->GetName() == this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModelName(j)) if (this->gazeboLocalID == tmp_gazebo_id)
{ {
// Original part unsigned int tmp_model_count = this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelCount();
model->LoadPlugins(); for (unsigned int j = 0; j < tmp_model_count; j++)
// Original part {
if (model->GetName() == this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelName(j))
{
// Original part
model->LoadPlugins();
// Original part
this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->SetModelID(j, model->GetId());
this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->models.push_back(model);
}
}
}
else
{
unsigned int tmp_model_count = this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelCount();
for (unsigned int j = 0; j < tmp_model_count; j++)
{
if (model->GetName() == this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelName(j))
{
this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->SetModelID(j, model->GetId());
this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->models.push_back(model);
}
}
} }
} }
} }
@ -1860,6 +1926,7 @@ void World::LoadPlugins()
{ {
model->LoadPlugins(); model->LoadPlugins();
} }
// Modified by zhangshuai 2019.04.02 ----End // Modified by zhangshuai 2019.04.02 ----End
// model->LoadPlugins(); // model->LoadPlugins();
} }
@ -2404,6 +2471,7 @@ void World::ProcessFactoryMsgs()
model->LoadPlugins(); model->LoadPlugins();
// Original part // Original part
this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->SetModelID(i, model->GetId()); this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->SetModelID(i, model->GetId());
this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->models.push_back(model); // modified by zhangshuai 2019.07.10
} }
} }
} }
@ -2415,6 +2483,7 @@ void World::ProcessFactoryMsgs()
if (model->GetName() == this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelName(i)) if (model->GetName() == this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelName(i))
{ {
this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->SetModelID(i, model->GetId()); this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->SetModelID(i, model->GetId());
this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->models.push_back(model); // modified by zhangshuai 2019.07.10
} }
} }
} }