1. MPI_Allgatherv, version 0.5.2
2. add "ownModels" list and some functions in world files, for MPI, "ownModels" are used for modelUpdteFunc 3. delete "models" list in GazeboID 4. add launch file that 30 hector takeoff 20 hector do not move for testing collision time
This commit is contained in:
parent
4b59599399
commit
aa80c5b61b
|
@ -127,16 +127,3 @@ 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];
|
|
||||||
}
|
|
|
@ -90,14 +90,6 @@ public:
|
||||||
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:
|
||||||
sdf::ElementPtr sdf;
|
sdf::ElementPtr sdf;
|
||||||
|
@ -113,10 +105,6 @@ 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
|
||||||
|
|
|
@ -1349,6 +1349,18 @@ ModelPtr World::LoadModel(sdf::ElementPtr _sdf, BasePtr _parent)
|
||||||
|
|
||||||
this->PublishModelPose(model);
|
this->PublishModelPose(model);
|
||||||
this->dataPtr->models.push_back(model);
|
this->dataPtr->models.push_back(model);
|
||||||
|
// Added by zhangshuai for MPI 2019.07.11 ----Begin
|
||||||
|
if (this->flag == 1)
|
||||||
|
{
|
||||||
|
for (unsigned int i = 0; i < this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModelCount(); i++)
|
||||||
|
{
|
||||||
|
if (model->GetName() == this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModelName(i))
|
||||||
|
{
|
||||||
|
this->dataPtr->ownModels.push_back(model);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// Added by zhangshuai for MPI 2019.07.11 ----End
|
||||||
return model;
|
return model;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1846,9 +1858,9 @@ void World::ModelUpdateSingleLoop()
|
||||||
// Modified by zhangshuai for MPI 2019.07.11 ----Begin
|
// Modified by zhangshuai for MPI 2019.07.11 ----Begin
|
||||||
if (this->flag == 1)
|
if (this->flag == 1)
|
||||||
{
|
{
|
||||||
for (unsigned int i = 0; i < this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModelCount(); i++)
|
for (unsigned int i = 0; i < this->GetOwnModelCount(); i++)
|
||||||
{
|
{
|
||||||
this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModel(i)->Update();
|
this->GetOwnModel(i)->Update();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
|
@ -1913,7 +1925,6 @@ void World::LoadPlugins()
|
||||||
model->LoadPlugins();
|
model->LoadPlugins();
|
||||||
// Original part
|
// Original part
|
||||||
this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->SetModelID(j, model->GetId());
|
this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->SetModelID(j, model->GetId());
|
||||||
this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->models.push_back(model);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1925,7 +1936,6 @@ void World::LoadPlugins()
|
||||||
if (model->GetName() == this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelName(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)->SetModelID(j, model->GetId());
|
||||||
this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->models.push_back(model);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -2480,7 +2490,6 @@ 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
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -2492,7 +2501,6 @@ 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
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -3431,3 +3439,24 @@ int World::GetFlag()
|
||||||
return this->flag;
|
return this->flag;
|
||||||
}
|
}
|
||||||
// Added by zhangshuai 2019.04.02 ----End
|
// Added by zhangshuai 2019.04.02 ----End
|
||||||
|
|
||||||
|
// Added by zhangshuai for MPI 2019.07.11 ----Begin
|
||||||
|
//////////////////////////////////////////////////
|
||||||
|
unsigned int World::GetOwnModelCount() const
|
||||||
|
{
|
||||||
|
return this->dataPtr->ownModels.size();
|
||||||
|
}
|
||||||
|
|
||||||
|
//////////////////////////////////////////////////
|
||||||
|
ModelPtr World::GetOwnModel(unsigned int _index) const
|
||||||
|
{
|
||||||
|
if (_index >= this->dataPtr->ownModels.size())
|
||||||
|
{
|
||||||
|
gzerr << "Given model index[" << _index << "] is out of range[0.."
|
||||||
|
<< this->dataPtr->models.size() << "]\n";
|
||||||
|
return ModelPtr();
|
||||||
|
}
|
||||||
|
|
||||||
|
return this->dataPtr->ownModels[_index];
|
||||||
|
}
|
||||||
|
// Added by zhangshuai for MPI 2019.07.11 ----End
|
|
@ -776,6 +776,22 @@ private:
|
||||||
// public:
|
// public:
|
||||||
// int GetFlag();
|
// int GetFlag();
|
||||||
// Added by zhangshuai 2019.06.10 ----End
|
// Added by zhangshuai 2019.06.10 ----End
|
||||||
|
|
||||||
|
// Added by zhangshuai for MPI 2019.07.11 ----Begin
|
||||||
|
/// \brief Get the number of own models.
|
||||||
|
/// \return The number of own models in the World.
|
||||||
|
public:
|
||||||
|
unsigned int GetOwnModelCount() const;
|
||||||
|
|
||||||
|
/// \brief Get a model based on an index.
|
||||||
|
/// Get a Model using an index, where index must be greater than zero
|
||||||
|
/// and less than World::GetOwnModelCount()
|
||||||
|
/// \param[in] _index The index of the model [0..GetOwnModelCount)
|
||||||
|
/// \return A pointer to the Model. NULL if _index is invalid.
|
||||||
|
public:
|
||||||
|
ModelPtr GetOwnModel(unsigned int _index) const;
|
||||||
|
// Added by zhangshuai for MPI 2019.07.11 ----End
|
||||||
|
|
||||||
};
|
};
|
||||||
/// \}
|
/// \}
|
||||||
} // namespace physics
|
} // namespace physics
|
||||||
|
|
|
@ -336,6 +336,11 @@ namespace gazebo
|
||||||
|
|
||||||
/// \brief Simulation time of the last log state captured.
|
/// \brief Simulation time of the last log state captured.
|
||||||
public: gazebo::common::Time logLastStateTime;
|
public: gazebo::common::Time logLastStateTime;
|
||||||
|
|
||||||
|
// Added by zhangshuai for MPI 2019.07.11 ----Begin
|
||||||
|
/// \brief A cached list of models to simulated in local Gazebo for MPI. This is here for performance.
|
||||||
|
public: Model_V ownModels;
|
||||||
|
// Added by zhangshuai for MPI 2019.07.11 ----End
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -70,7 +70,7 @@ do
|
||||||
echo "${hosts[$i]}:roslaunch_good"
|
echo "${hosts[$i]}:roslaunch_good"
|
||||||
done
|
done
|
||||||
|
|
||||||
sleep 20s
|
sleep 40s
|
||||||
|
|
||||||
#登入各节点开始仿真
|
#登入各节点开始仿真
|
||||||
for((i=0;i<host_count;i++))
|
for((i=0;i<host_count;i++))
|
||||||
|
@ -81,9 +81,9 @@ do
|
||||||
echo "${hosts[$i]}:start_good"
|
echo "${hosts[$i]}:start_good"
|
||||||
done
|
done
|
||||||
|
|
||||||
sleep 1m
|
sleep 5m
|
||||||
|
|
||||||
#登入各节点kill相关进程以结束仿真(1.目前方式比较暴力,后续改进;2.cd ~/MPI 还要进行灵活性优化)
|
#登入各节点kill相关进程以结束仿真(1.目前方式比较暴力,后续改进;2.cd ~/Git/Gazebo_Distributed_MPI/mpi_run 还要进行灵活性优化)
|
||||||
for((i=0;i<host_count;i++))
|
for((i=0;i<host_count;i++))
|
||||||
do
|
do
|
||||||
ssh -f -n ${hosts[$i]} > /dev/null 2>&1 "cd ~/Git/Gazebo_Distributed_MPI/mpi_run;
|
ssh -f -n ${hosts[$i]} > /dev/null 2>&1 "cd ~/Git/Gazebo_Distributed_MPI/mpi_run;
|
||||||
|
|
|
@ -0,0 +1,558 @@
|
||||||
|
<!-- This is a launch file that runs the bare minimum requirements to get -->
|
||||||
|
<!-- gazebo running for a fixed-wing aircraft -->
|
||||||
|
|
||||||
|
<launch>
|
||||||
|
|
||||||
|
<group ns="bebop_0">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_0" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_0" />
|
||||||
|
<arg name="x" value="0.0" />
|
||||||
|
<arg name="y" value="0.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_1">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_1" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_1" />
|
||||||
|
<arg name="x" value="0.0" />
|
||||||
|
<arg name="y" value="5.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_2">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_2" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_2" />
|
||||||
|
<arg name="x" value="0.0" />
|
||||||
|
<arg name="y" value="10.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_3">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_3" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_3" />
|
||||||
|
<arg name="x" value="0.0" />
|
||||||
|
<arg name="y" value="15.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_4">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_4" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_4" />
|
||||||
|
<arg name="x" value="0.0" />
|
||||||
|
<arg name="y" value="20.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_5">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_5" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_5" />
|
||||||
|
<arg name="x" value="0.0" />
|
||||||
|
<arg name="y" value="25.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_6">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_6" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_6" />
|
||||||
|
<arg name="x" value="0.0" />
|
||||||
|
<arg name="y" value="30.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_7">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_7" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_7" />
|
||||||
|
<arg name="x" value="0.0" />
|
||||||
|
<arg name="y" value="35.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_8">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_8" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_8" />
|
||||||
|
<arg name="x" value="0.0" />
|
||||||
|
<arg name="y" value="40.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_9">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_9" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_9" />
|
||||||
|
<arg name="x" value="0.0" />
|
||||||
|
<arg name="y" value="45.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_10">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_10" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_10" />
|
||||||
|
<arg name="x" value="5.0" />
|
||||||
|
<arg name="y" value="0.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_11">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_11" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_11" />
|
||||||
|
<arg name="x" value="5.0" />
|
||||||
|
<arg name="y" value="5.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_12">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_12" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_12" />
|
||||||
|
<arg name="x" value="5.0" />
|
||||||
|
<arg name="y" value="10.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_13">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_13" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_13" />
|
||||||
|
<arg name="x" value="5.0" />
|
||||||
|
<arg name="y" value="15.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_14">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_14" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_14" />
|
||||||
|
<arg name="x" value="5.0" />
|
||||||
|
<arg name="y" value="20.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_15">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_15" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_15" />
|
||||||
|
<arg name="x" value="5.0" />
|
||||||
|
<arg name="y" value="25.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_16">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_16" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_16" />
|
||||||
|
<arg name="x" value="5.0" />
|
||||||
|
<arg name="y" value="30.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_17">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_17" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_17" />
|
||||||
|
<arg name="x" value="5.0" />
|
||||||
|
<arg name="y" value="35.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_18">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_18" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_18" />
|
||||||
|
<arg name="x" value="5.0" />
|
||||||
|
<arg name="y" value="40.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_19">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_19" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_19" />
|
||||||
|
<arg name="x" value="5.0" />
|
||||||
|
<arg name="y" value="45.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_20">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_20" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_20" />
|
||||||
|
<arg name="x" value="10.0" />
|
||||||
|
<arg name="y" value="0.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_21">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_21" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_21" />
|
||||||
|
<arg name="x" value="10.0" />
|
||||||
|
<arg name="y" value="5.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_22">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_22" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_22" />
|
||||||
|
<arg name="x" value="10.0" />
|
||||||
|
<arg name="y" value="10.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_23">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_23" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_23" />
|
||||||
|
<arg name="x" value="10.0" />
|
||||||
|
<arg name="y" value="15.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_24">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_24" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_24" />
|
||||||
|
<arg name="x" value="10.0" />
|
||||||
|
<arg name="y" value="20.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_25">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_25" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_25" />
|
||||||
|
<arg name="x" value="10.0" />
|
||||||
|
<arg name="y" value="25.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_26">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_26" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_26" />
|
||||||
|
<arg name="x" value="10.0" />
|
||||||
|
<arg name="y" value="30.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_27">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_27" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_27" />
|
||||||
|
<arg name="x" value="10.0" />
|
||||||
|
<arg name="y" value="35.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_28">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_28" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_28" />
|
||||||
|
<arg name="x" value="10.0" />
|
||||||
|
<arg name="y" value="40.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_29">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_29" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_29" />
|
||||||
|
<arg name="x" value="10.0" />
|
||||||
|
<arg name="y" value="45.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_30">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_30" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_30" />
|
||||||
|
<arg name="x" value="15.0" />
|
||||||
|
<arg name="y" value="0.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_31">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_31" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_31" />
|
||||||
|
<arg name="x" value="15.0" />
|
||||||
|
<arg name="y" value="5.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_32">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_32" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_32" />
|
||||||
|
<arg name="x" value="15.0" />
|
||||||
|
<arg name="y" value="10.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_33">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_33" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_33" />
|
||||||
|
<arg name="x" value="15.0" />
|
||||||
|
<arg name="y" value="15.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_34">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_34" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_34" />
|
||||||
|
<arg name="x" value="15.0" />
|
||||||
|
<arg name="y" value="20.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_35">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_35" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_35" />
|
||||||
|
<arg name="x" value="15.0" />
|
||||||
|
<arg name="y" value="25.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_36">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_36" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_36" />
|
||||||
|
<arg name="x" value="15.0" />
|
||||||
|
<arg name="y" value="30.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_37">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_37" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_37" />
|
||||||
|
<arg name="x" value="15.0" />
|
||||||
|
<arg name="y" value="35.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_38">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_38" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_38" />
|
||||||
|
<arg name="x" value="15.0" />
|
||||||
|
<arg name="y" value="40.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_39">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_39" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_39" />
|
||||||
|
<arg name="x" value="15.0" />
|
||||||
|
<arg name="y" value="45.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_40">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_40" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_40" />
|
||||||
|
<arg name="x" value="20.0" />
|
||||||
|
<arg name="y" value="0.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_41">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_41" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_41" />
|
||||||
|
<arg name="x" value="20.0" />
|
||||||
|
<arg name="y" value="5.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_42">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_42" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_42" />
|
||||||
|
<arg name="x" value="20.0" />
|
||||||
|
<arg name="y" value="10.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_43">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_43" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_43" />
|
||||||
|
<arg name="x" value="20.0" />
|
||||||
|
<arg name="y" value="15.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_44">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_44" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_44" />
|
||||||
|
<arg name="x" value="20.0" />
|
||||||
|
<arg name="y" value="20.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_45">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_45" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_45" />
|
||||||
|
<arg name="x" value="20.0" />
|
||||||
|
<arg name="y" value="25.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_46">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_46" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_46" />
|
||||||
|
<arg name="x" value="20.0" />
|
||||||
|
<arg name="y" value="30.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_47">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_47" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_47" />
|
||||||
|
<arg name="x" value="20.0" />
|
||||||
|
<arg name="y" value="35.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_48">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_48" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_48" />
|
||||||
|
<arg name="x" value="20.0" />
|
||||||
|
<arg name="y" value="40.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<group ns="bebop_49">
|
||||||
|
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||||
|
<arg name="name" value="bebop_49" />
|
||||||
|
<arg name="model" value="$(find hector_quadrotor_description)/urdf/quadrotor_with_downward_cam.gazebo.xacro"/>
|
||||||
|
<arg name="tf_prefix" value="bebop_49" />
|
||||||
|
<arg name="x" value="20.0" />
|
||||||
|
<arg name="y" value="45.0" />
|
||||||
|
<arg name="z" value="0.186" />
|
||||||
|
</include>
|
||||||
|
</group>
|
||||||
|
|
||||||
|
<node name="simple_takeoff" pkg="hector" type="hector_simple_takeoff"/>
|
||||||
|
|
||||||
|
</launch>
|
Loading…
Reference in New Issue