1. MPI_Allgatherv, version 0.4.0
2. modify the process of Assignment and Value Pose to reduce execution time of MPI Module, the whole Speedup ratio reaches about 20 rather to initial MPI_Allgatherv version
This commit is contained in:
parent
d0ac7fddd0
commit
899036df93
|
@ -79,27 +79,13 @@ void GazeboID::Load(sdf::ElementPtr _sdf)
|
|||
if (this->sdf->HasAttribute("num"))
|
||||
this->gazeboID = this->sdf->Get<int>("num");
|
||||
|
||||
if (this->sdf->HasAttribute("ip"))
|
||||
this->ip = this->sdf->Get<std::string>("ip");
|
||||
|
||||
// if (this->sdf->HasElement("ip"))
|
||||
// {
|
||||
// sdf::ElementPtr gazeboIdElem = this->sdf->GetElement("ip");
|
||||
// ip = gazeboIdElem->Get<std::string>();
|
||||
// }
|
||||
|
||||
// if (this->sdf->HasElement("port"))
|
||||
// {
|
||||
// sdf::ElementPtr gazeboPortElem = this->sdf->GetElement("port");
|
||||
// port = gazeboPortElem->Get<int>();
|
||||
// }
|
||||
|
||||
if (this->sdf->HasElement("model_name"))
|
||||
{
|
||||
sdf::ElementPtr modelNameElem = this->sdf->GetElement("model_name");
|
||||
while (modelNameElem)
|
||||
{
|
||||
modelNames.push_back(modelNameElem->Get<std::string>());
|
||||
modelIDs.push_back(0); //initial state is 0
|
||||
modelNameElem = modelNameElem->GetNextElement("model_name");
|
||||
}
|
||||
}
|
||||
|
@ -111,12 +97,6 @@ int GazeboID::GetGazeboID()
|
|||
return gazeboID;
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////
|
||||
std::string GazeboID::GetGazeboIp()
|
||||
{
|
||||
return ip;
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////
|
||||
unsigned int GazeboID::GetModelCount()
|
||||
{
|
||||
|
@ -129,6 +109,18 @@ std::string GazeboID::GetModelName(unsigned int _i)
|
|||
return modelNames[_i];
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////
|
||||
unsigned int GazeboID::GetModelID(unsigned int _i)
|
||||
{
|
||||
return modelIDs[_i];
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////
|
||||
void GazeboID::SetModelID(unsigned int _i, unsigned int _id)
|
||||
{
|
||||
modelIDs[_i] = _id;
|
||||
}
|
||||
|
||||
//////////////////////////////////////////////////
|
||||
void GazeboID::Fini()
|
||||
{
|
||||
|
|
|
@ -63,11 +63,6 @@ public:
|
|||
public:
|
||||
int GetGazeboID();
|
||||
|
||||
/// \brief Get the gazebo ip of this Distribution.
|
||||
/// \return the gazebo ip of this Distribution.
|
||||
public:
|
||||
std::string GetGazeboIp();
|
||||
|
||||
/// \brief Get the number of models this Distribution has.
|
||||
/// \return Number of models associated with this Distribution.
|
||||
public:
|
||||
|
@ -79,6 +74,18 @@ public:
|
|||
public:
|
||||
std::string GetModelName(unsigned int _i);
|
||||
|
||||
/// \brief Get the ID of the specified model.
|
||||
/// \param[in] _i Number of the model ID to get.
|
||||
/// \return the ID of the specified model.
|
||||
public:
|
||||
unsigned int GetModelID(unsigned int _i);
|
||||
|
||||
/// \brief Set the ID of the specified model.
|
||||
/// \param[in] _i Number of the model to set ID.
|
||||
/// \param[in] _id ID of the model to set.
|
||||
public:
|
||||
void SetModelID(unsigned int _i, unsigned int _id);
|
||||
|
||||
/// \brief Finialize the gazeboID
|
||||
public:
|
||||
void Fini();
|
||||
|
@ -91,17 +98,13 @@ private:
|
|||
private:
|
||||
int gazeboID;
|
||||
|
||||
/// \brief ip of distributed gazebo.
|
||||
private:
|
||||
std::string ip;
|
||||
|
||||
/// \brief port of distributed gazebo.
|
||||
private:
|
||||
int port;
|
||||
|
||||
/// \brief Models name in this gazebo
|
||||
private:
|
||||
std::vector<std::string> modelNames;
|
||||
|
||||
/// \brief Models ID in this gazebo
|
||||
private:
|
||||
std::vector<unsigned int> modelIDs;
|
||||
};
|
||||
|
||||
} // namespace physics
|
||||
|
|
|
@ -29,18 +29,15 @@
|
|||
#include "gazebo/util/system.hh"
|
||||
#include "gazebo/math/Pose.hh"
|
||||
|
||||
#define QUEUE 1
|
||||
#define BUF_SIZE 8192
|
||||
|
||||
namespace gazebo
|
||||
{
|
||||
namespace physics
|
||||
{
|
||||
|
||||
/// \brief Structure of Pose information communicated with Tcp
|
||||
/// \brief Structure of Pose information communicated with MPI
|
||||
struct CommunicationData
|
||||
{
|
||||
char model_name[16];
|
||||
// char model_name[16];
|
||||
math::Pose model_pose;
|
||||
};
|
||||
|
||||
|
|
|
@ -951,15 +951,8 @@ void World::Update()
|
|||
CommunicationData *sendBufferData = new CommunicationData[tmp_local_model_count];
|
||||
for (unsigned int i = 0; i < tmp_local_model_count; i++)
|
||||
{
|
||||
std::string tmp_model_name = this->distribution->GetGazeboIDPtr(this->gazeboLocalID)->GetModelName(i);
|
||||
unsigned int j = 0;
|
||||
|
||||
for (j = 0; j < tmp_model_name.length(); j++)
|
||||
sendBufferData[i].model_name[j] = tmp_model_name[j];
|
||||
sendBufferData[i].model_name[j] = '\0';
|
||||
sendBufferData[i].model_pose = this->GetModel(tmp_model_name)->GetLink("canonical")->GetWorldPose();
|
||||
|
||||
tmp_model_name.clear();
|
||||
// sendBufferData[i].model_pose = this->GetModel(tmp_model_name)->GetLink("canonical")->GetWorldPose();
|
||||
sendBufferData[i].model_pose = this->GetModelById(this->distribution->GetGazeboIDPtr(this->gazeboLocalID)->GetModelID(i))->GetWorldPose();
|
||||
}
|
||||
|
||||
sendBuffer = (char *)sendBufferData;
|
||||
|
@ -1010,9 +1003,8 @@ void World::Update()
|
|||
|
||||
for (unsigned int i = 0; i < tmp_model_count; i++)
|
||||
{
|
||||
std::string tmp_model_name = tmpBufferData[i].model_name;
|
||||
this->GetModel(tmp_model_name)->GetLink("canonical")->SetWorldPose(tmpBufferData[i].model_pose);
|
||||
tmp_model_name.clear();
|
||||
// this->GetModel(tmp_model_name)->GetLink("canonical")->SetWorldPose(tmpBufferData[i].model_pose);
|
||||
this->GetModelById(this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelID(i))->SetWorldPose(tmpBufferData[i].model_pose);
|
||||
}
|
||||
delete[] tmpBufferData;
|
||||
}
|
||||
|
@ -2385,13 +2377,45 @@ void World::ProcessFactoryMsgs()
|
|||
if (this->flag == 1)
|
||||
{
|
||||
// Judge if the model to load is simulated in this gazebo
|
||||
for (unsigned int i = 0; i < this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModelCount(); i++)
|
||||
|
||||
// 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(i))
|
||||
if (this->gazeboLocalID == tmp_gazebo_id)
|
||||
{
|
||||
unsigned int tmp_model_count = this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelCount();
|
||||
for (unsigned int i = 0; i < tmp_model_count; i++)
|
||||
{
|
||||
if (model->GetName() == this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelName(i))
|
||||
{
|
||||
// Original part
|
||||
model->LoadPlugins();
|
||||
// Original part
|
||||
this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->SetModelID(i, model->GetId());
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
unsigned int tmp_model_count = this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelCount();
|
||||
for (unsigned int i = 0; i < tmp_model_count; i++)
|
||||
{
|
||||
if (model->GetName() == this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->GetModelName(i))
|
||||
{
|
||||
this->distribution->GetGazeboIDPtr(tmp_gazebo_id)->SetModelID(i, model->GetId());
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,448 @@
|
|||
<!-- 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>
|
||||
|
||||
<node name="simple_takeoff" pkg="hector" type="hector_simple_takeoff"/>
|
||||
|
||||
</launch>
|
|
@ -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>
|
|
@ -445,7 +445,7 @@
|
|||
|
||||
<group ns="bebop_40">
|
||||
<include file="$(find hector_quadrotor_gazebo)/launch/spawn_quadrotor.launch">
|
||||
<arg name="name" value="bebop_140" />
|
||||
<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" />
|
||||
|
|
|
@ -0,0 +1,385 @@
|
|||
<?xml version="1.0" ?>
|
||||
<sdf version="1.4">
|
||||
<world name="default">
|
||||
<!-- A global light source -->
|
||||
<include>
|
||||
<uri>model://sun</uri>
|
||||
</include>
|
||||
|
||||
<include>
|
||||
<uri>model://kunming_airport</uri>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
</include>
|
||||
|
||||
<scene>
|
||||
<ambient>0.68 0.68 0.68 1.0</ambient>
|
||||
<sky>
|
||||
<sunrise/>
|
||||
<clouds>
|
||||
<speed>0</speed>
|
||||
</clouds>
|
||||
</sky>
|
||||
</scene>
|
||||
|
||||
<!-- For distributed simulation -->
|
||||
<distribution flag=1>
|
||||
<gazebo_id num=0>
|
||||
<model_name>bebop_0</model_name>
|
||||
<model_name>bebop_1</model_name>
|
||||
<model_name>bebop_2</model_name>
|
||||
<model_name>bebop_3</model_name>
|
||||
<model_name>bebop_4</model_name>
|
||||
<model_name>bebop_5</model_name>
|
||||
<model_name>bebop_6</model_name>
|
||||
<model_name>bebop_7</model_name>
|
||||
<model_name>bebop_8</model_name>
|
||||
<model_name>bebop_9</model_name>
|
||||
<model_name>bebop_10</model_name>
|
||||
<model_name>bebop_11</model_name>
|
||||
<model_name>bebop_12</model_name>
|
||||
<model_name>bebop_13</model_name>
|
||||
<model_name>bebop_14</model_name>
|
||||
<model_name>bebop_15</model_name>
|
||||
<model_name>bebop_16</model_name>
|
||||
<model_name>bebop_17</model_name>
|
||||
<model_name>bebop_18</model_name>
|
||||
<model_name>bebop_19</model_name>
|
||||
<model_name>bebop_20</model_name>
|
||||
<model_name>bebop_21</model_name>
|
||||
<model_name>bebop_22</model_name>
|
||||
<model_name>bebop_23</model_name>
|
||||
<model_name>bebop_24</model_name>
|
||||
<model_name>bebop_25</model_name>
|
||||
<model_name>bebop_26</model_name>
|
||||
<model_name>bebop_27</model_name>
|
||||
<model_name>bebop_28</model_name>
|
||||
<model_name>bebop_29</model_name>
|
||||
<model_name>bebop_30</model_name>
|
||||
<model_name>bebop_31</model_name>
|
||||
<model_name>bebop_32</model_name>
|
||||
<model_name>bebop_33</model_name>
|
||||
<model_name>bebop_34</model_name>
|
||||
<model_name>bebop_35</model_name>
|
||||
<model_name>bebop_36</model_name>
|
||||
<model_name>bebop_37</model_name>
|
||||
<model_name>bebop_38</model_name>
|
||||
<model_name>bebop_39</model_name>
|
||||
<model_name>bebop_40</model_name>
|
||||
<model_name>bebop_41</model_name>
|
||||
<model_name>bebop_42</model_name>
|
||||
<model_name>bebop_43</model_name>
|
||||
<model_name>bebop_44</model_name>
|
||||
<model_name>bebop_45</model_name>
|
||||
<model_name>bebop_46</model_name>
|
||||
<model_name>bebop_47</model_name>
|
||||
<model_name>bebop_48</model_name>
|
||||
<model_name>bebop_49</model_name>
|
||||
</gazebo_id>
|
||||
<gazebo_id num=1>
|
||||
<model_name>bebop_50</model_name>
|
||||
<model_name>bebop_51</model_name>
|
||||
<model_name>bebop_52</model_name>
|
||||
<model_name>bebop_53</model_name>
|
||||
<model_name>bebop_54</model_name>
|
||||
<model_name>bebop_55</model_name>
|
||||
<model_name>bebop_56</model_name>
|
||||
<model_name>bebop_57</model_name>
|
||||
<model_name>bebop_58</model_name>
|
||||
<model_name>bebop_59</model_name>
|
||||
<model_name>bebop_60</model_name>
|
||||
<model_name>bebop_61</model_name>
|
||||
<model_name>bebop_62</model_name>
|
||||
<model_name>bebop_63</model_name>
|
||||
<model_name>bebop_64</model_name>
|
||||
<model_name>bebop_65</model_name>
|
||||
<model_name>bebop_66</model_name>
|
||||
<model_name>bebop_67</model_name>
|
||||
<model_name>bebop_68</model_name>
|
||||
<model_name>bebop_69</model_name>
|
||||
<model_name>bebop_70</model_name>
|
||||
<model_name>bebop_71</model_name>
|
||||
<model_name>bebop_72</model_name>
|
||||
<model_name>bebop_73</model_name>
|
||||
<model_name>bebop_74</model_name>
|
||||
<model_name>bebop_75</model_name>
|
||||
<model_name>bebop_76</model_name>
|
||||
<model_name>bebop_77</model_name>
|
||||
<model_name>bebop_78</model_name>
|
||||
<model_name>bebop_79</model_name>
|
||||
<model_name>bebop_80</model_name>
|
||||
<model_name>bebop_81</model_name>
|
||||
<model_name>bebop_82</model_name>
|
||||
<model_name>bebop_83</model_name>
|
||||
<model_name>bebop_84</model_name>
|
||||
<model_name>bebop_85</model_name>
|
||||
<model_name>bebop_86</model_name>
|
||||
<model_name>bebop_87</model_name>
|
||||
<model_name>bebop_88</model_name>
|
||||
<model_name>bebop_89</model_name>
|
||||
<model_name>bebop_90</model_name>
|
||||
<model_name>bebop_91</model_name>
|
||||
<model_name>bebop_92</model_name>
|
||||
<model_name>bebop_93</model_name>
|
||||
<model_name>bebop_94</model_name>
|
||||
<model_name>bebop_95</model_name>
|
||||
<model_name>bebop_96</model_name>
|
||||
<model_name>bebop_97</model_name>
|
||||
<model_name>bebop_98</model_name>
|
||||
<model_name>bebop_99</model_name>
|
||||
</gazebo_id>
|
||||
</distribution>
|
||||
|
||||
<physics type="ode" name="ode">
|
||||
<real_time_update_rate>0</real_time_update_rate>
|
||||
<max_step_size>0.001</max_step_size>
|
||||
<real_time_factor>0</real_time_factor>
|
||||
<!-- <ode>
|
||||
<solver>
|
||||
<thread_position_correction>0</thread_position_correction>
|
||||
<island_threads>8</island_threads>
|
||||
</solver>
|
||||
</ode> -->
|
||||
</physics>
|
||||
|
||||
<!-- <model name="bebop_0">
|
||||
<pose>0 0 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_1">
|
||||
<pose>0 5 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_2">
|
||||
<pose>0 10 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_3">
|
||||
<pose>0 15 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_4">
|
||||
<pose>0 20 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_5">
|
||||
<pose>0 25 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_6">
|
||||
<pose>0 30 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_7">
|
||||
<pose>0 35 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_8">
|
||||
<pose>0 40 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_9">
|
||||
<pose>0 45 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_10">
|
||||
<pose>5 0 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_11">
|
||||
<pose>5 5 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_12">
|
||||
<pose>5 10 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_13">
|
||||
<pose>5 15 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_14">
|
||||
<pose>5 20 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_15">
|
||||
<pose>5 25 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_16">
|
||||
<pose>5 30 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_17">
|
||||
<pose>5 35 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_18">
|
||||
<pose>5 40 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_19">
|
||||
<pose>5 45 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_20">
|
||||
<pose>10 0 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_21">
|
||||
<pose>10 5 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_22">
|
||||
<pose>10 10 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_23">
|
||||
<pose>10 15 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_24">
|
||||
<pose>10 20 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_25">
|
||||
<pose>10 25 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_26">
|
||||
<pose>10 30 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_27">
|
||||
<pose>10 35 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_28">
|
||||
<pose>10 40 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_29">
|
||||
<pose>10 45 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model> -->
|
||||
|
||||
</world>
|
||||
</sdf>
|
|
@ -0,0 +1,325 @@
|
|||
<?xml version="1.0" ?>
|
||||
<sdf version="1.4">
|
||||
<world name="default">
|
||||
<!-- A global light source -->
|
||||
<include>
|
||||
<uri>model://sun</uri>
|
||||
</include>
|
||||
|
||||
<include>
|
||||
<uri>model://kunming_airport</uri>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
</include>
|
||||
|
||||
<scene>
|
||||
<ambient>0.68 0.68 0.68 1.0</ambient>
|
||||
<sky>
|
||||
<sunrise/>
|
||||
<clouds>
|
||||
<speed>0</speed>
|
||||
</clouds>
|
||||
</sky>
|
||||
</scene>
|
||||
|
||||
<!-- For distributed simulation -->
|
||||
<distribution flag=1>
|
||||
<gazebo_id num=0>
|
||||
<model_name>bebop_0</model_name>
|
||||
<model_name>bebop_1</model_name>
|
||||
<model_name>bebop_2</model_name>
|
||||
<model_name>bebop_3</model_name>
|
||||
<model_name>bebop_4</model_name>
|
||||
<model_name>bebop_5</model_name>
|
||||
<model_name>bebop_6</model_name>
|
||||
<model_name>bebop_7</model_name>
|
||||
<model_name>bebop_8</model_name>
|
||||
<model_name>bebop_9</model_name>
|
||||
<model_name>bebop_10</model_name>
|
||||
<model_name>bebop_11</model_name>
|
||||
<model_name>bebop_12</model_name>
|
||||
<model_name>bebop_13</model_name>
|
||||
<model_name>bebop_14</model_name>
|
||||
<model_name>bebop_15</model_name>
|
||||
<model_name>bebop_16</model_name>
|
||||
<model_name>bebop_17</model_name>
|
||||
<model_name>bebop_18</model_name>
|
||||
<model_name>bebop_19</model_name>
|
||||
</gazebo_id>
|
||||
<gazebo_id num=1>
|
||||
<model_name>bebop_20</model_name>
|
||||
<model_name>bebop_21</model_name>
|
||||
<model_name>bebop_22</model_name>
|
||||
<model_name>bebop_23</model_name>
|
||||
<model_name>bebop_24</model_name>
|
||||
<model_name>bebop_25</model_name>
|
||||
<model_name>bebop_26</model_name>
|
||||
<model_name>bebop_27</model_name>
|
||||
<model_name>bebop_28</model_name>
|
||||
<model_name>bebop_29</model_name>
|
||||
<model_name>bebop_30</model_name>
|
||||
<model_name>bebop_31</model_name>
|
||||
<model_name>bebop_32</model_name>
|
||||
<model_name>bebop_33</model_name>
|
||||
<model_name>bebop_34</model_name>
|
||||
<model_name>bebop_35</model_name>
|
||||
<model_name>bebop_36</model_name>
|
||||
<model_name>bebop_37</model_name>
|
||||
<model_name>bebop_38</model_name>
|
||||
<model_name>bebop_39</model_name>
|
||||
</gazebo_id>
|
||||
</distribution>
|
||||
|
||||
<physics type="ode" name="ode">
|
||||
<real_time_update_rate>0</real_time_update_rate>
|
||||
<max_step_size>0.001</max_step_size>
|
||||
<real_time_factor>0</real_time_factor>
|
||||
<!-- <ode>
|
||||
<solver>
|
||||
<thread_position_correction>0</thread_position_correction>
|
||||
<island_threads>8</island_threads>
|
||||
</solver>
|
||||
</ode> -->
|
||||
</physics>
|
||||
|
||||
<!-- <model name="bebop_0">
|
||||
<pose>0 0 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_1">
|
||||
<pose>0 5 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_2">
|
||||
<pose>0 10 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_3">
|
||||
<pose>0 15 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_4">
|
||||
<pose>0 20 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_5">
|
||||
<pose>0 25 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_6">
|
||||
<pose>0 30 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_7">
|
||||
<pose>0 35 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_8">
|
||||
<pose>0 40 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_9">
|
||||
<pose>0 45 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_10">
|
||||
<pose>5 0 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_11">
|
||||
<pose>5 5 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_12">
|
||||
<pose>5 10 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_13">
|
||||
<pose>5 15 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_14">
|
||||
<pose>5 20 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_15">
|
||||
<pose>5 25 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_16">
|
||||
<pose>5 30 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_17">
|
||||
<pose>5 35 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_18">
|
||||
<pose>5 40 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_19">
|
||||
<pose>5 45 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_20">
|
||||
<pose>10 0 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_21">
|
||||
<pose>10 5 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_22">
|
||||
<pose>10 10 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_23">
|
||||
<pose>10 15 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_24">
|
||||
<pose>10 20 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_25">
|
||||
<pose>10 25 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_26">
|
||||
<pose>10 30 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_27">
|
||||
<pose>10 35 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_28">
|
||||
<pose>10 40 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_29">
|
||||
<pose>10 45 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model> -->
|
||||
|
||||
</world>
|
||||
</sdf>
|
|
@ -0,0 +1,335 @@
|
|||
<?xml version="1.0" ?>
|
||||
<sdf version="1.4">
|
||||
<world name="default">
|
||||
<!-- A global light source -->
|
||||
<include>
|
||||
<uri>model://sun</uri>
|
||||
</include>
|
||||
|
||||
<include>
|
||||
<uri>model://kunming_airport</uri>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
</include>
|
||||
|
||||
<scene>
|
||||
<ambient>0.68 0.68 0.68 1.0</ambient>
|
||||
<sky>
|
||||
<sunrise/>
|
||||
<clouds>
|
||||
<speed>0</speed>
|
||||
</clouds>
|
||||
</sky>
|
||||
</scene>
|
||||
|
||||
<!-- For distributed simulation -->
|
||||
<distribution flag=1>
|
||||
<gazebo_id num=0>
|
||||
<model_name>bebop_0</model_name>
|
||||
<model_name>bebop_1</model_name>
|
||||
<model_name>bebop_2</model_name>
|
||||
<model_name>bebop_3</model_name>
|
||||
<model_name>bebop_4</model_name>
|
||||
<model_name>bebop_5</model_name>
|
||||
<model_name>bebop_6</model_name>
|
||||
<model_name>bebop_7</model_name>
|
||||
<model_name>bebop_8</model_name>
|
||||
<model_name>bebop_9</model_name>
|
||||
<model_name>bebop_10</model_name>
|
||||
<model_name>bebop_11</model_name>
|
||||
<model_name>bebop_12</model_name>
|
||||
<model_name>bebop_13</model_name>
|
||||
<model_name>bebop_14</model_name>
|
||||
<model_name>bebop_15</model_name>
|
||||
<model_name>bebop_16</model_name>
|
||||
<model_name>bebop_17</model_name>
|
||||
<model_name>bebop_18</model_name>
|
||||
<model_name>bebop_19</model_name>
|
||||
<model_name>bebop_20</model_name>
|
||||
<model_name>bebop_21</model_name>
|
||||
<model_name>bebop_22</model_name>
|
||||
<model_name>bebop_23</model_name>
|
||||
<model_name>bebop_24</model_name>
|
||||
</gazebo_id>
|
||||
<gazebo_id num=1>
|
||||
<model_name>bebop_25</model_name>
|
||||
<model_name>bebop_26</model_name>
|
||||
<model_name>bebop_27</model_name>
|
||||
<model_name>bebop_28</model_name>
|
||||
<model_name>bebop_29</model_name>
|
||||
<model_name>bebop_30</model_name>
|
||||
<model_name>bebop_31</model_name>
|
||||
<model_name>bebop_32</model_name>
|
||||
<model_name>bebop_33</model_name>
|
||||
<model_name>bebop_34</model_name>
|
||||
<model_name>bebop_35</model_name>
|
||||
<model_name>bebop_36</model_name>
|
||||
<model_name>bebop_37</model_name>
|
||||
<model_name>bebop_38</model_name>
|
||||
<model_name>bebop_39</model_name>
|
||||
<model_name>bebop_40</model_name>
|
||||
<model_name>bebop_41</model_name>
|
||||
<model_name>bebop_42</model_name>
|
||||
<model_name>bebop_43</model_name>
|
||||
<model_name>bebop_44</model_name>
|
||||
<model_name>bebop_45</model_name>
|
||||
<model_name>bebop_46</model_name>
|
||||
<model_name>bebop_47</model_name>
|
||||
<model_name>bebop_48</model_name>
|
||||
<model_name>bebop_49</model_name>
|
||||
</gazebo_id>
|
||||
</distribution>
|
||||
|
||||
<physics type="ode" name="ode">
|
||||
<real_time_update_rate>0</real_time_update_rate>
|
||||
<max_step_size>0.001</max_step_size>
|
||||
<real_time_factor>0</real_time_factor>
|
||||
<!-- <ode>
|
||||
<solver>
|
||||
<thread_position_correction>0</thread_position_correction>
|
||||
<island_threads>8</island_threads>
|
||||
</solver>
|
||||
</ode> -->
|
||||
</physics>
|
||||
|
||||
<!-- <model name="bebop_0">
|
||||
<pose>0 0 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_1">
|
||||
<pose>0 5 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_2">
|
||||
<pose>0 10 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_3">
|
||||
<pose>0 15 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_4">
|
||||
<pose>0 20 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_5">
|
||||
<pose>0 25 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_6">
|
||||
<pose>0 30 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_7">
|
||||
<pose>0 35 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_8">
|
||||
<pose>0 40 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_9">
|
||||
<pose>0 45 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_10">
|
||||
<pose>5 0 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_11">
|
||||
<pose>5 5 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_12">
|
||||
<pose>5 10 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_13">
|
||||
<pose>5 15 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_14">
|
||||
<pose>5 20 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_15">
|
||||
<pose>5 25 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_16">
|
||||
<pose>5 30 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_17">
|
||||
<pose>5 35 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_18">
|
||||
<pose>5 40 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_19">
|
||||
<pose>5 45 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_20">
|
||||
<pose>10 0 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_21">
|
||||
<pose>10 5 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_22">
|
||||
<pose>10 10 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_23">
|
||||
<pose>10 15 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_24">
|
||||
<pose>10 20 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_25">
|
||||
<pose>10 25 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_26">
|
||||
<pose>10 30 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_27">
|
||||
<pose>10 35 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_28">
|
||||
<pose>10 40 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model>
|
||||
|
||||
<model name="bebop_29">
|
||||
<pose>10 45 0.186 0 0 0</pose>
|
||||
<include>
|
||||
<uri>model://quadrotor</uri>
|
||||
</include>
|
||||
<plugin name="takeoff" filename="/home/zhangshuai/gazebo_plugin_tutorial/takeoff/build/libtakeoff.so"/>
|
||||
</model> -->
|
||||
|
||||
</world>
|
||||
</sdf>
|
Loading…
Reference in New Issue