Skip to content

Commit

Permalink
Merge pull request #639 from PeterBowman/imu-orientation
Browse files Browse the repository at this point in the history
Reference initial orientation to world frame in IMU plugin
  • Loading branch information
traversaro committed Mar 10, 2023
2 parents 34c08b6 + 1559f55 commit 4b35f02
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 1 deletion.
6 changes: 5 additions & 1 deletion CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,11 @@ The format of this document is based on [Keep a Changelog](https://keepachangelo

## [Unreleased]

### Fixed
### Changed

- The `gazebo_imu` plugin used to output orientation measurements as if the sensor was zero-aligned with the world frame, regardless of the initial orientation of the part the sensor is attached to. To match most real-world IMUs, the default behavior was changed to allow measuring orientation with regard to the world frame at all times. The old behavior can be restored by setting the `useInitialSensorOrientationAsReference` config option (https://github.com/robotology/gazebo-yarp-plugins/pull/639).

### Fixed

- Fix wrong install include for gazebo_yarp_lib_common library (https://github.com/robotology/gazebo-yarp-plugins/pull/644).

Expand Down
3 changes: 3 additions & 0 deletions plugins/imu/src/IMU.cc
Original file line number Diff line number Diff line change
Expand Up @@ -152,6 +152,9 @@ void GazeboYarpIMU::Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf)
{"sensor_name", ::yarp::os::Value{_sensor->Name()}}
};

if (m_parameters.check("useInitialSensorOrientationAsReference")) {
imu_properties.put("useInitialSensorOrientationAsReference", yarp::os::Value::getNullValue());
}

//Open the driver
if (!m_imuDriver.open(imu_properties)) {
Expand Down
6 changes: 6 additions & 0 deletions plugins/imu/src/IMUDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@
#include <yarp/os/Log.h>
#include <yarp/os/LogStream.h>

#include <ignition/math/Quaternion.hh>

using namespace boost::placeholders;

using namespace yarp::dev;
Expand Down Expand Up @@ -88,6 +90,10 @@ bool GazeboYarpIMUDriver::open(yarp::os::Searchable& config)
return false;
}

if (!config.check("useInitialSensorOrientationAsReference")) {
m_parentSensor->SetWorldToReferenceOrientation(ignition::math::Quaterniond::Identity);
}

//Connect the driver to the gazebo simulation
using namespace boost::placeholders;
this->m_updateConnection = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboYarpIMUDriver::onUpdate, this, _1));
Expand Down

0 comments on commit 4b35f02

Please sign in to comment.