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

5 ➡️ 6 (main) #155

Merged
merged 14 commits into from
Sep 21, 2021
59 changes: 59 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,41 @@

### Ignition Sensors 4.X.X

### Ignition Sensors 4.2.0 (2021-07-12)

1. Add API for enabling / disabling IMU orientation
* [Pull request #142](https://github.com/ignitionrobotics/ign-sensors/pull/142)

1. Init will now set the nextUpdateTime to zero
* [Pull request #137](https://github.com/ignitionrobotics/ign-sensors/pull/137)

1. Remove clamping from lidar noise
* [Pull request #132](https://github.com/ignitionrobotics/ign-sensors/pull/132)

1. Remove tools/code_check and update codecov
* [Pull request #130](https://github.com/ignitionrobotics/ign-sensors/pull/130)

1. Disable macOS workflow
* [Pull request #124](https://github.com/ignitionrobotics/ign-sensors/pull/124)

1. 👩‍🌾 Disable tests that consistently fail on macOS
* [Pull request #121](https://github.com/ignitionrobotics/ign-sensors/pull/121)

1. Master branch updates
* [Pull request #106](https://github.com/ignitionrobotics/ign-sensors/pull/106)

1. 👩‍🌾 Clear Windows warnings (backport #58)
* [Pull request #102](https://github.com/ignitionrobotics/ign-sensors/pull/102)

1. Update thermal camera tutorial - include varying temp. objects
* [Pull request #79](https://github.com/ignitionrobotics/ign-sensors/pull/79)

1. Fix macOS/windows tests that failed to load library
* [Pull request #60](https://github.com/ignitionrobotics/ign-sensors/pull/60)

1. Removed issue & PR templates
* [Pull request #99](https://github.com/ignitionrobotics/ign-sensors/pull/99)

### Ignition Sensors 4.1.0 (2021-02-10)

1. Added issue and PR templates.
Expand Down Expand Up @@ -72,6 +107,30 @@

## Ignition Sensors 3

### Ignition Sensors 3.X.X (202X-XX-XX)

### Ignition Sensors 3.3.0 (2021-08-26)

1. 👩‍🌾 Print debug messages when sensors advertise topics
* [Pull request #151](https://github.com/ignitionrobotics/ign-sensors/pull/151)

1. Publish performance sensor metrics.
* [Pull request #146](https://github.com/ignitionrobotics/ign-sensors/pull/146)

1. CI and infrastructure
* [Pull request #130](https://github.com/ignitionrobotics/ign-sensors/pull/130)
* [Pull request #150](https://github.com/ignitionrobotics/ign-sensors/pull/150)
* [Pull request #106](https://github.com/ignitionrobotics/ign-sensors/pull/106)

1. 👩‍🌾 Disable tests that consistently fail on macOS
* [Pull request #121](https://github.com/ignitionrobotics/ign-sensors/pull/121)

1. 👩‍🌾 Clear Windows warnings (backport #58)
* [Pull request #58](https://github.com/ignitionrobotics/ign-sensors/pull/58)

1. Fix macOS/windows tests that failed to load library (backport #60)
* [Pull request #60](https://github.com/ignitionrobotics/ign-sensors/pull/60)

### Ignition Sensors 3.2.0 (2021-02-08)

1. Apply noise to lidar point cloud.
Expand Down
88 changes: 0 additions & 88 deletions bitbucket-pipelines.yml

This file was deleted.

16 changes: 15 additions & 1 deletion include/ignition/sensors/ImuSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -111,13 +111,27 @@ namespace ignition
public: math::Quaterniond OrientationReference() const;

/// \brief Get the orienation of the imu with respect to reference frame
/// \return Orientation in reference frame
/// \return Orientation in reference frame. If orientation is not
/// enabled, this will return the last computed orientation before
/// orientation is disabled or identity Quaternion if orientation has
/// never been enabled.
public: math::Quaterniond Orientation() const;

/// \brief Set the gravity vector
/// \param[in] _gravity gravity vector in meters per second squared.
public: void SetGravity(const math::Vector3d &_gravity);

/// \brief Set whether to output orientation. Not all imu's generate
/// orientation values as they use filters to produce orientation
/// estimates.
/// \param[in] _enabled True to publish orientation data, false to leave
/// the message field empty.
public: void SetOrientationEnabled(bool _enabled);

/// \brief Get whether or not orientation is enabled.
/// \return True if orientation is enabled, false otherwise.
public: bool OrientationEnabled() const;

/// \brief Get the gravity vector
/// \return Gravity vectory in meters per second squared.
public: math::Vector3d Gravity() const;
Expand Down
15 changes: 15 additions & 0 deletions include/ignition/sensors/Sensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#pragma warning(pop)
#endif

#include <chrono>
#include <memory>
#include <string>

Expand Down Expand Up @@ -150,6 +151,14 @@ namespace ignition
/// \return True if a valid topic was set.
public: bool SetTopic(const std::string &_topic);

/// \brief Get flag state for enabling performance metrics publication.
/// \return True if performance metrics are enabled, false otherwise.
public: bool EnableMetrics() const;

/// \brief Set flag to enable publishing performance metrics
/// \param[in] _enableMetrics True to enable.
public: void SetEnableMetrics(bool _enableMetrics);

/// \brief Get parent link of the sensor.
/// \return Parent link of sensor.
public: std::string Parent() const;
Expand Down Expand Up @@ -184,6 +193,12 @@ namespace ignition
public: void AddSequence(ignition::msgs::Header *_msg,
const std::string &_seqKey = "default");

/// \brief Publishes information about the performance of the sensor.
/// This method is called by Update().
/// \param[in] _now Current time.
public: void PublishMetrics(
const std::chrono::duration<double> &_now);

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \internal
/// \brief Data pointer for private data
Expand Down
3 changes: 3 additions & 0 deletions src/AirPressureSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -122,6 +122,9 @@ bool AirPressureSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Air pressure for [" << this->Name() << "] advertised on ["
<< this->Topic() << "]" << std::endl;

// Load the noise parameters
if (_sdf.AirPressureSensor()->PressureNoise().Type() != sdf::NoiseType::NONE)
{
Expand Down
3 changes: 3 additions & 0 deletions src/AltimeterSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,9 @@ bool AltimeterSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Altimeter data for [" << this->Name() << "] advertised on ["
<< this->Topic() << "]" << std::endl;

// Load the noise parameters
if (_sdf.AltimeterSensor()->VerticalPositionNoise().Type()
!= sdf::NoiseType::NONE)
Expand Down
21 changes: 10 additions & 11 deletions src/CameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -268,6 +268,9 @@ bool CameraSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Camera images for [" << this->Name() << "] advertised on ["
<< this->Topic() << "]" << std::endl;

if (!this->AdvertiseInfo())
return false;

Expand Down Expand Up @@ -500,16 +503,7 @@ bool CameraSensor::AdvertiseInfo()
}
this->dataPtr->infoTopic += "/camera_info";

this->dataPtr->infoPub =
this->dataPtr->node.Advertise<ignition::msgs::CameraInfo>(
this->dataPtr->infoTopic);
if (!this->dataPtr->infoPub)
{
ignerr << "Unable to create publisher on topic["
<< this->dataPtr->infoTopic << "].\n";
}

return this->dataPtr->infoPub;
return this->AdvertiseInfo(this->dataPtr->infoTopic);
}

//////////////////////////////////////////////////
Expand All @@ -522,9 +516,14 @@ bool CameraSensor::AdvertiseInfo(const std::string &_topic)
this->dataPtr->infoTopic);
if (!this->dataPtr->infoPub)
{
ignerr << "Unable to create publisher on topic["
ignerr << "Unable to create publisher on topic ["
<< this->dataPtr->infoTopic << "].\n";
}
else
{
igndbg << "Camera info for [" << this->Name() << "] advertised on ["
<< this->dataPtr->infoTopic << "]" << std::endl;
}

return this->dataPtr->infoPub;
}
Expand Down
6 changes: 6 additions & 0 deletions src/DepthCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -284,6 +284,9 @@ bool DepthCameraSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Depth images for [" << this->Name() << "] advertised on ["
<< this->Topic() << "]" << std::endl;

if (!this->AdvertiseInfo())
return false;

Expand All @@ -298,6 +301,9 @@ bool DepthCameraSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Points for [" << this->Name() << "] advertised on ["
<< this->Topic() << "/points]" << std::endl;

// Initialize the point message.
// \todo(anyone) The true value in the following function call forces
// the xyz and rgb fields to be aligned to memory boundaries. This is need
Expand Down
3 changes: 3 additions & 0 deletions src/GpuLidarSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -146,6 +146,9 @@ bool GpuLidarSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Lidar points for [" << this->Name() << "] advertised on ["
<< this->Topic() << "]" << std::endl;

this->initialized = true;

return true;
Expand Down
35 changes: 28 additions & 7 deletions src/ImuSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,9 @@ class ignition::sensors::ImuSensorPrivate
/// \brief transform to Imu frame from Imu reference frame.
public: ignition::math::Quaterniond orientation;

/// \brief True to publish orientation data.
public: bool orientationEnabled = true;

/// \brief store gravity vector to be added to the IMU output.
public: ignition::math::Vector3d gravity;

Expand Down Expand Up @@ -125,6 +128,9 @@ bool ImuSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "IMU data for [" << this->Name() << "] advertised on ["
<< this->Topic() << "]" << std::endl;

const std::map<SensorNoiseType, sdf::Noise> noises = {
{ACCELEROMETER_X_NOISE_M_S_S, _sdf.ImuSensor()->LinearAccelerationXNoise()},
{ACCELEROMETER_Y_NOISE_M_S_S, _sdf.ImuSensor()->LinearAccelerationYNoise()},
Expand Down Expand Up @@ -204,20 +210,23 @@ bool ImuSensor::Update(const std::chrono::steady_clock::duration &_now)
applyNoise(GYROSCOPE_Y_NOISE_RAD_S, this->dataPtr->angularVel.Y());
applyNoise(GYROSCOPE_Z_NOISE_RAD_S, this->dataPtr->angularVel.Z());

// Set the IMU orientation
// imu orientation with respect to reference frame
this->dataPtr->orientation =
this->dataPtr->orientationReference.Inverse() *
this->dataPtr->worldPose.Rot();

msgs::IMU msg;
*msg.mutable_header()->mutable_stamp() = msgs::Convert(_now);
msg.set_entity_name(this->Name());
auto frame = msg.mutable_header()->add_data();
frame->set_key("frame_id");
frame->add_value(this->Name());

msgs::Set(msg.mutable_orientation(), this->dataPtr->orientation);
if (this->dataPtr->orientationEnabled)
{
// Set the IMU orientation
// imu orientation with respect to reference frame
this->dataPtr->orientation =
this->dataPtr->orientationReference.Inverse() *
this->dataPtr->worldPose.Rot();

msgs::Set(msg.mutable_orientation(), this->dataPtr->orientation);
}
msgs::Set(msg.mutable_angular_velocity(), this->dataPtr->angularVel);
msgs::Set(msg.mutable_linear_acceleration(), this->dataPtr->linearAcc);

Expand Down Expand Up @@ -277,6 +286,18 @@ math::Quaterniond ImuSensor::OrientationReference() const
return this->dataPtr->orientationReference;
}

//////////////////////////////////////////////////
void ImuSensor::SetOrientationEnabled(bool _enabled)
{
this->dataPtr->orientationEnabled = _enabled;
}

//////////////////////////////////////////////////
bool ImuSensor::OrientationEnabled() const
{
return this->dataPtr->orientationEnabled;
}

//////////////////////////////////////////////////
void ImuSensor::SetGravity(const math::Vector3d &_gravity)
{
Expand Down
Loading