Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

IMU sensor API to get world ref frame and heading offset #186

Merged
merged 24 commits into from
Mar 4, 2022
Merged
Show file tree
Hide file tree
Changes from 21 commits
Commits
Show all changes
24 commits
Select commit Hold shift + click to select a range
17ca1ac
Added basic logic to parse localization frames
adityapande-1995 Jan 11, 2022
d4aa659
Minor cleanup
adityapande-1995 Jan 11, 2022
c479887
Added transformation quaternions to convert frames
adityapande-1995 Jan 11, 2022
1fdc240
Added enum type, review changes
adityapande-1995 Jan 13, 2022
eaa94cd
codecheck fixes
adityapande-1995 Jan 14, 2022
59d0b08
Added testcases
adityapande-1995 Jan 14, 2022
d09f508
Cleanup for codecheck
adityapande-1995 Jan 14, 2022
324ed90
Merge branch 'ign-sensors6' into aditya/named_frames_imu
adityapande-1995 Jan 14, 2022
7bdfb0b
Localization tag parsing moved to a separate method
adityapande-1995 Jan 19, 2022
e16ab67
Changed variable names and docstrings
adityapande-1995 Jan 20, 2022
2e5e910
static const transformTable added
adityapande-1995 Jan 24, 2022
df783de
Added documentation for WorlfFrameEnum
adityapande-1995 Jan 26, 2022
3ead9f2
Address not mapped to object error
adityapande-1995 Jan 27, 2022
0f99a51
Removed debug prints
adityapande-1995 Feb 2, 2022
368a24f
Intialize sensorOrientationRelativeTo
adityapande-1995 Feb 2, 2022
00e9c7c
Placed docstring with enum values
adityapande-1995 Feb 3, 2022
18b3645
Linter fix
adityapande-1995 Feb 3, 2022
33a79c6
Account for heading with CUSTOM refernce frame
adityapande-1995 Feb 4, 2022
8f03ce1
Fixed typos, renamed helper function
adityapande-1995 Feb 14, 2022
654ceb8
Refactored tests
adityapande-1995 Feb 14, 2022
90f6917
Added test case: empty localization tag
adityapande-1995 Mar 1, 2022
3f42ba6
Added invalid localization tag test case
adityapande-1995 Mar 3, 2022
735a61f
changed variable names to lowerCamelCase
adityapande-1995 Mar 3, 2022
744d0d1
Merge branch 'ign-sensors6' into aditya/named_frames_imu
adityapande-1995 Mar 3, 2022
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
32 changes: 30 additions & 2 deletions include/ignition/sensors/ImuSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -33,9 +33,30 @@ namespace ignition
{
namespace sensors
{
// Inline bracket to help doxygen filtering.
/// Inline bracket to help doxygen filtering.
inline namespace IGNITION_SENSORS_VERSION_NAMESPACE {
//

/// \brief Reference frames enum
enum class IGNITION_SENSORS_VISIBLE WorldFrameEnumType
{
/// \brief NONE : To be used only when <localization>
/// reference orientation tag is empty.
NONE = 0,
scpeters marked this conversation as resolved.
Show resolved Hide resolved

/// \brief ENU (East-North-Up): x - East, y - North, z - Up.
ENU = 1,

/// \brief NED (North-East-Down): x - North, y - East, z - Down.
NED = 2,

/// \brief NWU (North-West-Up): x - North, y - West, z - Up.
NWU = 3,

/// \brief CUSTOM : The frame is described using custom_rpy tag.
CUSTOM = 4
};

///
/// \brief forward declarations
class ImuSensorPrivate;

Expand Down Expand Up @@ -136,6 +157,13 @@ namespace ignition
/// \return Gravity vectory in meters per second squared.
public: math::Vector3d Gravity() const;

/// \brief Specify the rotation offset of the coordinates of the World
/// frame relative to a geo-referenced frame
/// \param[in] _rot rotation offset
/// \param[in] _relativeTo world frame orientation, ENU by default
public: void SetWorldFrameOrientation(
const math::Quaterniond &_rot, WorldFrameEnumType _relativeTo);

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
Expand Down
124 changes: 106 additions & 18 deletions src/ImuSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,23 @@ class ignition::sensors::ImuSensorPrivate
/// \brief Flag for if time has been initialized
public: bool timeInitialized = false;

/// \brief Orientation of world frame relative to a specified frame
public: ignition::math::Quaterniond worldRelativeOrientation;

/// \brief Frame relative-to which the worldRelativeOrientation
// is defined
public: WorldFrameEnumType worldFrameRelativeTo = WorldFrameEnumType::ENU;

/// \brief Frame relative-to which the sensor orientation is reported
public: WorldFrameEnumType sensorOrientationRelativeTo
= WorldFrameEnumType::NONE;

/// \brief Frame realtive to which custom_rpy is specified
public: std::string CustomRpyParentFrame;
adityapande-1995 marked this conversation as resolved.
Show resolved Hide resolved

/// \brief Quaternion for to store custom_rpy
public: ignition::math::Quaterniond CustomRpyQuaternion;
adityapande-1995 marked this conversation as resolved.
Show resolved Hide resolved

/// \brief Previous update time step.
public: std::chrono::steady_clock::duration prevStep
{std::chrono::steady_clock::duration::zero()};
Expand Down Expand Up @@ -116,24 +133,6 @@ bool ImuSensor::Load(const sdf::Sensor &_sdf)
return false;
}

// Set orientation reference frame
// TODO(adityapande-1995) : Add support for named frames like
// ENU using ign-gazebo
if (_sdf.ImuSensor()->Localization() == "CUSTOM")
{
if (_sdf.ImuSensor()->CustomRpyParentFrame() == "")
{
this->SetOrientationReference(ignition::math::Quaterniond(
_sdf.ImuSensor()->CustomRpy()));
}
else
{
ignwarn << "custom_rpy parent frame must be set to empty "
"string. Setting it to any other frame is not "
"supported yet." << std::endl;
}
}

if (this->Topic().empty())
this->SetTopic("/imu");

Expand Down Expand Up @@ -166,6 +165,26 @@ bool ImuSensor::Load(const sdf::Sensor &_sdf)
}
}

std::string localization = _sdf.ImuSensor()->Localization();

if (localization == "ENU")
{
this->dataPtr->sensorOrientationRelativeTo = WorldFrameEnumType::ENU;
} else if (localization == "NED") {
this->dataPtr->sensorOrientationRelativeTo = WorldFrameEnumType::NED;
} else if (localization == "NWU") {
this->dataPtr->sensorOrientationRelativeTo = WorldFrameEnumType::NWU;
} else if (localization == "CUSTOM") {
this->dataPtr->sensorOrientationRelativeTo = WorldFrameEnumType::CUSTOM;
} else {
this->dataPtr->sensorOrientationRelativeTo = WorldFrameEnumType::NONE;
scpeters marked this conversation as resolved.
Show resolved Hide resolved
}

this->dataPtr->CustomRpyParentFrame =
_sdf.ImuSensor()->CustomRpyParentFrame();
this->dataPtr->CustomRpyQuaternion = ignition::math::Quaterniond(
_sdf.ImuSensor()->CustomRpy());

this->dataPtr->initialized = true;
return true;
}
Expand Down Expand Up @@ -292,6 +311,75 @@ math::Pose3d ImuSensor::WorldPose() const
return this->dataPtr->worldPose;
}

//////////////////////////////////////////////////
void ImuSensor::SetWorldFrameOrientation(
const math::Quaterniond &_rot, WorldFrameEnumType _relativeTo)
{
this->dataPtr->worldRelativeOrientation = _rot;
this->dataPtr->worldFrameRelativeTo = _relativeTo;

// Set orientation reference frame if custom_rpy was supplied
if (this->dataPtr->sensorOrientationRelativeTo == WorldFrameEnumType::CUSTOM)
{
if (this->dataPtr->CustomRpyParentFrame == "")
{
this->SetOrientationReference(this->dataPtr->worldRelativeOrientation *
this->dataPtr->CustomRpyQuaternion);
}
else
{
ignwarn << "custom_rpy parent frame must be set to empty "
"string. Setting it to any other frame is not "
"supported yet." << std::endl;
}
return;
}

// Table to hold frame transformations
static const std::map<WorldFrameEnumType,
std::map<WorldFrameEnumType, ignition::math::Quaterniond>>
transformTable =
{
{WorldFrameEnumType::ENU,
{
{WorldFrameEnumType::ENU, ignition::math::Quaterniond(0, 0, 0)},
{WorldFrameEnumType::NED, ignition::math::Quaterniond(
IGN_PI, 0, IGN_PI/2)},
{WorldFrameEnumType::NWU, ignition::math::Quaterniond(
0, 0, IGN_PI/2)},
}
},
{WorldFrameEnumType::NED,
{
{WorldFrameEnumType::ENU, ignition::math::Quaterniond(
IGN_PI, 0, IGN_PI/2).Inverse()},
{WorldFrameEnumType::NED, ignition::math::Quaterniond(0, 0, 0)},
{WorldFrameEnumType::NWU, ignition::math::Quaterniond(
-IGN_PI, 0, 0)},
}
},
{WorldFrameEnumType::NWU,
{
{WorldFrameEnumType::ENU, ignition::math::Quaterniond(
0, 0, -IGN_PI/2)},
{WorldFrameEnumType::NED, ignition::math::Quaterniond(IGN_PI, 0, 0)},
{WorldFrameEnumType::NWU, ignition::math::Quaterniond(0, 0, 0)},
}
}
};

if (this->dataPtr->sensorOrientationRelativeTo != WorldFrameEnumType::NONE &&
this->dataPtr->sensorOrientationRelativeTo != WorldFrameEnumType::CUSTOM)
{
// A valid named localization tag is supplied in the sdf
auto tranformation =
transformTable.at(this->dataPtr->worldFrameRelativeTo).at
(this->dataPtr->sensorOrientationRelativeTo);
this->SetOrientationReference(this->dataPtr->worldRelativeOrientation *
tranformation);
}
}

//////////////////////////////////////////////////
void ImuSensor::SetOrientationReference(const math::Quaterniond &_orient)
{
Expand Down
Loading