Skip to content

Commit

Permalink
Merged in gazebo_2.0 (pull request #733)
Browse files Browse the repository at this point in the history
Merge gazebo_2.0 to default
  • Loading branch information
scpeters committed Oct 2, 2013
2 parents 48c7baa + 225d016 commit ce60bf6
Show file tree
Hide file tree
Showing 7 changed files with 192 additions and 32 deletions.
7 changes: 4 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,12 +10,12 @@ string (TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER)
string (TOUPPER ${PROJECT_NAME} PROJECT_NAME_UPPER)

set (GAZEBO_VERSION_NAME "lithium")
set (GAZEBO_MAJOR_VERSION 1)
set (GAZEBO_MINOR_VERSION 9)
set (GAZEBO_MAJOR_VERSION 2)
set (GAZEBO_MINOR_VERSION 0)
# The patch version may have been bumped for prerelease purposes; be sure to
# check gazebo-release/ubuntu/debian/changelog@default to determine what the
# next patch version should be for a regular release.
set (GAZEBO_PATCH_VERSION 1)
set (GAZEBO_PATCH_VERSION 0)

set (GAZEBO_VERSION ${GAZEBO_MAJOR_VERSION}.${GAZEBO_MINOR_VERSION})
set (GAZEBO_VERSION_FULL ${GAZEBO_MAJOR_VERSION}.${GAZEBO_MINOR_VERSION}.${GAZEBO_PATCH_VERSION})
Expand Down Expand Up @@ -303,6 +303,7 @@ else (build_errors)
# Make the cmake config files
set(PKG_NAME ${PROJECT_NAME_UPPER})
set(PKG_LIBRARIES
gazebo
gazebo_ccd
gazebo_common
gazebo_gimpact
Expand Down
10 changes: 8 additions & 2 deletions gazebo/common/ModelDatabase.cc
Original file line number Diff line number Diff line change
Expand Up @@ -135,9 +135,13 @@ bool ModelDatabase::HasModel(const std::string &_modelURI)

// Make sure there is a URI separator
if (uriSeparator == std::string::npos)
{
gzerr << "No URI separator \"://\" in [" << _modelURI << "]\n";
return false;
}

boost::replace_first(uri, "model://", ModelDatabase::GetURI());
uri = uri.substr(0, uri.find("/", ModelDatabase::GetURI().size()));

std::map<std::string, std::string> models = ModelDatabase::GetModels();

Expand All @@ -147,6 +151,7 @@ bool ModelDatabase::HasModel(const std::string &_modelURI)
if (iter->first == uri)
return true;
}

return false;
}

Expand Down Expand Up @@ -423,9 +428,10 @@ std::string ModelDatabase::GetModelPath(const std::string &_uri,
size_t modelNameLen = endIndex == std::string::npos ? std::string::npos :
endIndex - startIndex;

modelName = modelName.substr(startIndex, modelNameLen);
if (endIndex != std::string::npos)
suffix = _uri.substr(endIndex, std::string::npos);
suffix = modelName.substr(endIndex, std::string::npos);

modelName = modelName.substr(startIndex, modelNameLen);

// Store downloaded .tar.gz and intermediate .tar files in temp location
boost::filesystem::path tmppath = boost::filesystem::temp_directory_path();
Expand Down
7 changes: 7 additions & 0 deletions gazebo/gui/GuiIface.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include "gazebo/gui/qt.h"
#include "gazebo/gazebo.hh"

#include "gazebo/common/ModelDatabase.hh"
#include "gazebo/common/Console.hh"
#include "gazebo/common/Plugin.hh"
#include "gazebo/common/CommonTypes.hh"
Expand Down Expand Up @@ -136,6 +137,9 @@ namespace gazebo
/////////////////////////////////////////////////
void fini()
{
// Cleanup model database.
common::ModelDatabase::Instance()->Fini();

gui::clear_active_camera();
rendering::fini();
fflush(stdout);
Expand Down Expand Up @@ -186,6 +190,9 @@ bool gui::run(int _argc, char **_argv)
// Initialize the informational logger. This will log warnings, and errors.
gazebo::common::Console::Instance()->Init("gzclient.log");

// Make sure the model database has started
gazebo::common::ModelDatabase::Instance()->Start();

if (!parse_args(_argc, _argv))
return false;

Expand Down
26 changes: 13 additions & 13 deletions gazebo/physics/Model.hh
Original file line number Diff line number Diff line change
Expand Up @@ -292,6 +292,19 @@ namespace gazebo
/// \return Number of sensors.
public: unsigned int GetSensorCount() const;

/// \brief Get a handle to the Controller for the joints in this model.
/// \return A handle to the Controller for the joints in this model.
public: JointControllerPtr GetJointController();

/// \brief Get a gripper based on an index.
/// \return A pointer to a Gripper. Null if the _index is invalid.
public: GripperPtr GetGripper(size_t _index) const;

/// \brief Get the number of grippers in this model.
/// \return Size of this->grippers array.
/// \sa Model::GetGripper()
public: size_t GetGripperCount() const;

/// \brief Callback when the pose of the model has been changed.
protected: virtual void OnPoseChange();

Expand All @@ -315,19 +328,6 @@ namespace gazebo
/// \param[in] _name Name of the link to remove.
private: void RemoveLink(const std::string &_name);

/// \brief Get a handle to the Controller for the joints in this model.
/// \return A handle to the Controller for the joints in this model.
public: JointControllerPtr GetJointController();

/// \brief Get a gripper based on an index.
/// \return A pointer to a Gripper. Null if the _index is invalid.
public: GripperPtr GetGripper(size_t _index) const;

/// \brief Get the number of grippers in this model.
/// \return Size of this->grippers array.
/// \sa Model::GetGripper()
public: size_t GetGripperCount() const;

/// used by Model::AttachStaticModel
protected: std::vector<ModelPtr> attachedModels;

Expand Down
15 changes: 8 additions & 7 deletions gazebo/rendering/Heightmap.cc
Original file line number Diff line number Diff line change
Expand Up @@ -254,6 +254,7 @@ void Heightmap::Load()
{
nTerrains = this->NumTerrainSubdivisions;
}
double sqrtN = sqrt(nTerrains);

// Create terrain group, which holds all the individual terrain instances.
// Param 1: Pointer to the scene manager
Expand All @@ -264,17 +265,17 @@ void Heightmap::Load()

this->terrainGroup = new Ogre::TerrainGroup(
this->scene->GetManager(), Ogre::Terrain::ALIGN_X_Y,
1 + ((this->dataSize - 1) / sqrt(nTerrains)),
this->terrainSize.x / (sqrt(nTerrains)));
1 + ((this->dataSize - 1) / sqrtN),
this->terrainSize.x / (sqrtN));

boost::filesystem::path prefix = this->pagingPath / "gazebo_terrain";
this->terrainGroup->setFilenameConvention(
Ogre::String(prefix.string()), Ogre::String("dat"));

Ogre::Vector3 orig = Conversions::Convert(this->terrainOrigin);
math::Vector3 origin(
-0.5 * this->terrainSize.x + 0.5 * this->terrainSize.x / sqrt(nTerrains),
-0.5 * this->terrainSize.x + 0.5 * this->terrainSize.x / sqrt(nTerrains),
orig.x -0.5 * this->terrainSize.x + 0.5 * this->terrainSize.x / sqrtN,
orig.y -0.5 * this->terrainSize.x + 0.5 * this->terrainSize.x / sqrtN,
orig.z);

this->terrainGroup->setOrigin(Conversions::Convert(origin));
Expand Down Expand Up @@ -305,11 +306,11 @@ void Heightmap::Load()
this->terrainPaging->createWorldSection(world, this->terrainGroup,
this->LoadRadiusFactor * this->terrainSize.x,
this->HoldRadiusFactor * this->terrainSize.x,
0, 0, sqrt(nTerrains) - 1, sqrt(nTerrains) - 1);
0, 0, sqrtN - 1, sqrtN - 1);
}

for (int y = 0; y <= sqrt(nTerrains) - 1; ++y)
for (int x = 0; x <= sqrt(nTerrains) - 1; ++x)
for (int y = 0; y <= sqrtN - 1; ++y)
for (int x = 0; x <= sqrtN - 1; ++x)
this->DefineTerrain(x, y);

// sync load since we want everything in place when we start
Expand Down
17 changes: 10 additions & 7 deletions gazebo/rendering/LaserVisual.cc
Original file line number Diff line number Diff line change
Expand Up @@ -40,24 +40,27 @@ LaserVisual::LaserVisual(const std::string &_name, VisualPtr _vis,
this->node = transport::NodePtr(new transport::Node());
this->node->Init(this->scene->GetName());

this->laserScanSub = this->node->Subscribe(_topicName,
&LaserVisual::OnScan, this);

this->rayFan = this->CreateDynamicLine(rendering::RENDERING_TRIANGLE_FAN);

this->rayFan->setMaterial("Gazebo/BlueLaser");
this->rayFan->AddPoint(math::Vector3(0, 0, 0));
this->SetVisibilityFlags(GZ_VISIBILITY_GUI);

this->laserScanSub = this->node->Subscribe(_topicName,
&LaserVisual::OnScan, this);

this->connection = event::Events::ConnectPreRender(
boost::bind(&LaserVisual::Update, this));
}

/////////////////////////////////////////////////
LaserVisual::~LaserVisual()
{
delete this->rayFan;
this->rayFan = NULL;
if (this->rayFan)
{
this->DeleteDynamicLine(this->rayFan);
this->rayFan = NULL;
}
}

/////////////////////////////////////////////////
Expand All @@ -74,9 +77,9 @@ void LaserVisual::Update()
boost::mutex::scoped_lock lock(this->mutex);

// Skip the update if the user is moving the laser.
if (this->GetScene()->GetSelectedVisual() &&
if (!this->rayFan || (this->GetScene()->GetSelectedVisual() &&
this->GetRootVisual()->GetName() ==
this->GetScene()->GetSelectedVisual()->GetName())
this->GetScene()->GetSelectedVisual()->GetName()))
{
return;
}
Expand Down
142 changes: 142 additions & 0 deletions sdf/worlds/everything.world
Original file line number Diff line number Diff line change
@@ -0,0 +1,142 @@
<?xml version="1.0" ?>
<sdf version="1.4">
<world name="default">

<!-- A global light source -->
<include>
<uri>model://sun</uri>
</include>

<!-- A ground plane -->
<include>
<uri>model://ground_plane</uri>
</include>

<include>
<uri>model://pr2</uri>
<pose>0 0 0 0 0 0</pose>
</include>

<include>
<uri>model://house_1</uri>
<pose>10 0 0 0 0 0</pose>
</include>

<include>
<uri>model://house_2</uri>
<pose>20 0 0 0 0 0</pose>
</include>

<include>
<uri>model://house_3</uri>
<pose>30 0 0 0 0 0</pose>
</include>

<include>
<uri>model://jersey_barrier</uri>
<pose>40 0 0 0 0 0</pose>
</include>

<include>
<uri>model://bookshelf</uri>
<pose>50 0 0 0 0 0</pose>
</include>

<include>
<uri>model://turtlebot</uri>
<pose>60 0 0 0 0 0</pose>
</include>

<include>
<uri>model://table</uri>
<pose>70 0 0 0 0 0</pose>
</include>

<include>
<uri>model://willowgarage</uri>
<pose>100 0 0 0 0 0</pose>
</include>

<include>
<uri>model://youbot</uri>
<pose>-10 0 0 0 0 0</pose>
</include>

<include>
<uri>model://utility_cart</uri>
<pose>-20 0 0 0 0 0</pose>
</include>

<include>
<uri>model://stop_sign</uri>
<pose>-30 0 0 0 0 0</pose>
</include>

<include>
<uri>model://starting_pen</uri>
<pose>-40 0 0 0 0 0</pose>
</include>

<include>
<uri>model://speed_limit_sign</uri>
<pose>-50 0 0 0 0 0</pose>
</include>

<include>
<uri>model://powerplant</uri>
<pose>-80 0 0 0 0 0</pose>
</include>

<include>
<uri>model://polaris_ranger_ev</uri>
<pose>0 10 0 0 0 0</pose>
</include>

<include>
<uri>model://pioneer2dx</uri>
<pose>0 20 0 0 0 0</pose>
</include>

<include>
<uri>model://monkey_wrench</uri>
<pose>0 30 0 0 0 0</pose>
</include>

<include>
<uri>model://mailbox</uri>
<pose>0 40 0 0 0 0</pose>
</include>

<include>
<uri>model://lamp_post</uri>
<pose>0 50 0 0 0 0</pose>
</include>

<include>
<uri>model://hammer</uri>
<pose>0 60 0 0 0 0</pose>
</include>

<include>
<uri>model://grey_wall</uri>
<pose>0 70 0 0 0 0</pose>
</include>

<include>
<uri>model://gas_station</uri>
<pose>0 80 0 0 0 0</pose>
</include>

<include>
<uri>model://fast_food</uri>
<pose>0 90 0 0 0 0</pose>
</include>

<include>
<uri>model://dumpster</uri>
<pose>0 100 0 0 0 0</pose>
</include>

</world>
</sdf>

0 comments on commit ce60bf6

Please sign in to comment.