Skip to content

Commit

Permalink
Default to new behavior, make the old one opt-in
Browse files Browse the repository at this point in the history
  • Loading branch information
PeterBowman committed Mar 8, 2023
1 parent 6e94671 commit 1559f55
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 5 deletions.
4 changes: 2 additions & 2 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,9 @@ The format of this document is based on [Keep a Changelog](https://keepachangelo

## [Unreleased]

### Added
### Changed

- Added a new `useWorldReferenceOrientation` config option in the `gazebo_imu` plugin to take account for any initial non-zero orientation of the sensor as measured via `yarp::dev::IOrientationSensors` (https://github.com/robotology/gazebo-yarp-plugins/pull/639).
- 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

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

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

//Open the driver
Expand Down
2 changes: 1 addition & 1 deletion plugins/imu/src/IMUDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,7 @@ bool GazeboYarpIMUDriver::open(yarp::os::Searchable& config)
return false;
}

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

Expand Down

0 comments on commit 1559f55

Please sign in to comment.