Skip to content

Commit

Permalink
merged from gazebo7
Browse files Browse the repository at this point in the history
  • Loading branch information
chapulina committed Jun 20, 2017
2 parents fabd662 + 9624e06 commit 5fb430b
Show file tree
Hide file tree
Showing 26 changed files with 2,430 additions and 89 deletions.
4 changes: 2 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,11 @@ string (TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER)
string (TOUPPER ${PROJECT_NAME} PROJECT_NAME_UPPER)

set (GAZEBO_MAJOR_VERSION 7)
set (GAZEBO_MINOR_VERSION 7)
set (GAZEBO_MINOR_VERSION 8)
# 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 0)
set (GAZEBO_PATCH_VERSION 1)

set (GAZEBO_VERSION ${GAZEBO_MAJOR_VERSION}.${GAZEBO_MINOR_VERSION})
set (GAZEBO_VERSION_FULL ${GAZEBO_MAJOR_VERSION}.${GAZEBO_MINOR_VERSION}.${GAZEBO_PATCH_VERSION})
Expand Down
17 changes: 15 additions & 2 deletions Changelog.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,19 @@
## Gazebo 7

## Gazebo 7.X.X (201X-XX-XX)
## Gazebo 7.x.x (2017-xx-xx)

## Gazebo 7.8.1 (2017-06-08)

1. ODE slip parameter example world and test
* [Pull request 2717](https://bitbucket.org/osrf/gazebo/pull-request/2717)

1. Fix inserted mesh scale during log playback
* [Pull request #2723](https://bitbucket.org/osrf/gazebo/pull-request/2723)

## Gazebo 7.8.0 (2017-06-02)

1. Add log record filter options
* [Pull request 2715](https://bitbucket.org/osrf/gazebo/pull-request/2715)

1. Backport wide angle camera VM FSAA fix
* [Pull request 2711](https://bitbucket.org/osrf/gazebo/pull-request/2711)
Expand All @@ -24,7 +37,7 @@
* [Pull request 2669](https://bitbucket.org/osrf/gazebo/pull-request/2669)

1. Subdivide large heightmaps to fix LOD and support global texture mapping
* [Pull request 2655](https://bitbucket.org/osrf/gazebo/pull-request/2655)
* [Pull request 2655](https://bitbucket.org/osrf/gazebo/pull-request/2655)

## Gazebo 7.6.0 (2017-03-20)

Expand Down
19 changes: 19 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,25 @@ Deprecated code produces compile-time warnings. These warning serve as
notification to users that their code should be upgraded. The next major
release will remove the deprecated code.

## Gazebo 7.9.0 to 7.X

### Modifications

1. **gazebo/physics/ode/ODEPhysics.cc**
`ODEPhysics::Collide` combines surface slip parameters with a sum
instead of `std::min`.
Please see [Pull request 2717](https://bitbucket.org/osrf/gazebo/pull-request/2717)
for more details.

## Gazebo 7.8.0 to 7.X

### Modifications

1. **gz log**
Gazebo log files no longer store velocity data and have reduced floating point precision.
See [pull request 2715](https://bitbucket.org/osrf/gazebo/pull-requests/2715/add-log-record-filter-options)
for further details.

## Gazebo 7.3.1 to 7.X

### Deprecations
Expand Down
17 changes: 13 additions & 4 deletions gazebo/Server.cc
Original file line number Diff line number Diff line change
Expand Up @@ -155,6 +155,10 @@ bool Server::ParseArgs(int _argc, char **_argv)
"Compression encoding format for log data (zlib|bz2|txt).")
("record_path", po::value<std::string>()->default_value(""),
"Absolute path in which to store state data")
("record_period", po::value<double>()->default_value(-1),
"Recording period (seconds).")
("record_filter", po::value<std::string>()->default_value(""),
"Recording filter (supports wildcard and regular expression).")
("seed", po::value<double>(), "Start with a given random number seed.")
("iters", po::value<unsigned int>(), "Number of iterations to simulate.")
("minimal_comms", "Reduce the TCP/IP traffic output by gzserver")
Expand Down Expand Up @@ -252,9 +256,9 @@ bool Server::ParseArgs(int _argc, char **_argv)
if (this->dataPtr->vm.count("record"))
{
this->dataPtr->params["record"] =
this->dataPtr->vm["record_path"].as<std::string>();
this->dataPtr->vm["record_path"].as<std::string>();
this->dataPtr->params["record_encoding"] =
this->dataPtr->vm["record_encoding"].as<std::string>();
this->dataPtr->vm["record_encoding"].as<std::string>();
}

if (this->dataPtr->vm.count("iters"))
Expand Down Expand Up @@ -612,8 +616,13 @@ void Server::ProcessParams()
}
else if (iter->first == "record")
{
util::LogRecord::Instance()->Start(
this->dataPtr->params["record_encoding"], iter->second);
util::LogRecordParams params;

params.encoding = this->dataPtr->params["record_encoding"];
params.path = iter->second;
params.period = this->dataPtr->vm["record_period"].as<double>();
params.filter = this->dataPtr->vm["record_filter"].as<std::string>();
util::LogRecord::Instance()->Start(params);
}
}
}
Expand Down
4 changes: 4 additions & 0 deletions gazebo/gazebo.1.ronn
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,10 @@ Gazebo server runs simulation and handles commandline options, starts a Master,
Compression encoding format for log data (zlib|bz2|txt).
* --record_path arg :
Absolute path in which to store state data.
* --record_period arg (=-1) :
Recording period (seconds).
* --record_filter arg :
Recording filter (supports wildcard and regular expression).
* --seed arg :
Start with a given random number seed.
* --iters arg :
Expand Down
3 changes: 3 additions & 0 deletions gazebo/gazebo_main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,9 @@ void help()
<< " (zlib|bz2|txt).\n"
<< " --record_path arg Absolute path in which to store "
<< "state data.\n"
<< " --record_period arg (=-1) Recording period (seconds).\n"
<< " --record_filter arg Recording filter (supports wildcard and "
<< "regular expression).\n"
<< " --seed arg Start with a given random number seed.\n"
<< " --iters arg Number of iterations to simulate.\n"
<< " --minimal_comms Reduce the TCP/IP traffic output by "
Expand Down
4 changes: 4 additions & 0 deletions gazebo/gzserver.1.ronn
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,10 @@ Gazebo server runs simulation and handles commandline options, starts a Master,
Compression encoding format for log data (zlib|bz2|txt).
* --record_path arg :
Absolute path in which to store state data
* --record_period arg (=-1) :
Recording period (seconds).
* --record_filter arg :
Recording filter (supports wildcard and regular expression).
* --seed arg :
Start with a given random number seed.
* --iters arg :
Expand Down
16 changes: 16 additions & 0 deletions gazebo/physics/LinkState.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,10 @@
using namespace gazebo;
using namespace physics;

// TODO declared here for ABI compatibility
// move to class member variable when merging forward.
static bool gRecordVelocity = false;

/////////////////////////////////////////////////
LinkState::LinkState()
: State()
Expand Down Expand Up @@ -363,3 +367,15 @@ void LinkState::SetIterations(const uint64_t _iterations)
for (auto &collisionState : this->collisionStates)
collisionState.SetIterations(_iterations);
}

/////////////////////////////////////////////////
void LinkState::SetRecordVelocity(const bool _record)
{
gRecordVelocity = _record;
}

/////////////////////////////////////////////////
bool LinkState::RecordVelocity() const
{
return gRecordVelocity;
}
51 changes: 33 additions & 18 deletions gazebo/physics/LinkState.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#ifndef _LINKSTATE_HH_
#define _LINKSTATE_HH_

#include <iostream>
#include <vector>
#include <string>

Expand Down Expand Up @@ -189,28 +190,33 @@ namespace gazebo
const gazebo::physics::LinkState &_state)
{
math::Vector3 q(_state.pose.rot.GetAsEuler());
_out << std::fixed <<std::setprecision(5)
_out.unsetf(std::ios_base::floatfield);
_out << std::setprecision(4)
<< "<link name='" << _state.name << "'>"
<< "<pose>"
<< _state.pose.pos.x << " "
<< _state.pose.pos.y << " "
<< _state.pose.pos.z << " "
<< q.x << " "
<< q.y << " "
<< q.z << " "
<< ignition::math::precision(_state.pose.pos.x, 4) << " "
<< ignition::math::precision(_state.pose.pos.y, 4) << " "
<< ignition::math::precision(_state.pose.pos.z, 4) << " "
<< ignition::math::precision(q.x, 4) << " "
<< ignition::math::precision(q.y, 4) << " "
<< ignition::math::precision(q.z, 4) << " "
<< "</pose>";

/// Disabling this for efficiency.
q = _state.velocity.rot.GetAsEuler();
_out << std::fixed <<std::setprecision(4)
<< "<velocity>"
<< _state.velocity.pos.x << " "
<< _state.velocity.pos.y << " "
<< _state.velocity.pos.z << " "
<< q.x << " "
<< q.y << " "
<< q.z << " "
<< "</velocity>";
if (_state.RecordVelocity())
{
/// Disabling this for efficiency.
q = _state.velocity.rot.GetAsEuler();
_out.unsetf(std::ios_base::floatfield);
_out << std::setprecision(4)
<< "<velocity>"
<< ignition::math::precision(_state.velocity.pos.x, 4) << " "
<< ignition::math::precision(_state.velocity.pos.y, 4) << " "
<< ignition::math::precision(_state.velocity.pos.z, 4) << " "
<< ignition::math::precision(q.x, 4) << " "
<< ignition::math::precision(q.y, 4) << " "
<< ignition::math::precision(q.z, 4) << " "
<< "</velocity>";
}
// << "<acceleration>" << _state.acceleration << "</acceleration>"
// << "<wrench>" << _state.wrench << "</wrench>";

Expand All @@ -227,6 +233,15 @@ namespace gazebo
return _out;
}

/// \brief Set whether to record link velocity
/// \param[in] _record True to record link velocity, false to leave it
/// out of the log
public: void SetRecordVelocity(const bool _record);

/// \brief Get whether link velocity is recorded
/// \return True if link velocity is recorded
public: bool RecordVelocity() const;

/// \brief 3D pose of the link relative to the model.
private: math::Pose pose;

Expand Down
6 changes: 2 additions & 4 deletions gazebo/physics/Model.cc
Original file line number Diff line number Diff line change
Expand Up @@ -569,8 +569,7 @@ const sdf::ElementPtr Model::UnscaledSDF()
}
else if (geomElem->HasElement("mesh"))
{
geomElem->GetElement("mesh")->GetElement("scale")->Set(
ignition::math::Vector3d::One);
// Keep mesh scale because meshes can't be scaled yet (issue #1473)
}

visualElem = visualElem->GetNextElement("visual");
Expand Down Expand Up @@ -613,8 +612,7 @@ const sdf::ElementPtr Model::UnscaledSDF()
}
else if (geomElem->HasElement("mesh"))
{
geomElem->GetElement("mesh")->GetElement("scale")->Set(
ignition::math::Vector3d::One);
// Keep mesh scale because meshes can't be scaled yet (issue #1473)
}

collisionElem = collisionElem->GetNextElement("collision");
Expand Down
24 changes: 13 additions & 11 deletions gazebo/physics/ModelState.hh
Original file line number Diff line number Diff line change
Expand Up @@ -244,19 +244,21 @@ namespace gazebo
const gazebo::physics::ModelState &_state)
{
math::Vector3 q(_state.pose.rot.GetAsEuler());
_out << std::fixed <<std::setprecision(3)
_out.unsetf(std::ios_base::floatfield);
_out << std::setprecision(3)
<< "<model name='" << _state.GetName() << "'>"
<< "<pose>"
<< _state.pose.pos.x << " "
<< _state.pose.pos.y << " "
<< _state.pose.pos.z << " "
<< q.x << " "
<< q.y << " "
<< q.z << " "
<< "</pose>"
<< "<scale>"
<< _state.scale
<< "</scale>";
<< ignition::math::precision(_state.pose.pos.x, 4) << " "
<< ignition::math::precision(_state.pose.pos.y, 4) << " "
<< ignition::math::precision(_state.pose.pos.z, 4) << " "
<< ignition::math::precision(q.x, 4) << " "
<< ignition::math::precision(q.y, 4) << " "
<< ignition::math::precision(q.z, 4) << " "
<< "</pose>";

// Only record scale if it is not the default value of [1, 1, 1].
if (_state.scale != ignition::math::Vector3d::One)
_out << "<scale>" << _state.scale << "</scale>";

for (LinkState_M::const_iterator iter =
_state.linkStates.begin(); iter != _state.linkStates.end();
Expand Down
Loading

0 comments on commit 5fb430b

Please sign in to comment.