This repository was archived by the owner on Mar 18, 2025. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 18
Adds time interpolation to the Science Sensors #210
Merged
Merged
Changes from 2 commits
Commits
Show all changes
5 commits
Select commit
Hold shift + click to select a range
File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -30,6 +30,7 @@ | |
| #include <ignition/math/SphericalCoordinates.hh> | ||
| #include <ignition/math/VolumetricGridLookupField.hh> | ||
| #include <ignition/msgs/Utility.hh> | ||
| #include <ignition/msgs/stringmsg.pb.h> | ||
| #include <ignition/plugin/Register.hh> | ||
| #include <ignition/transport/Node.hh> | ||
|
|
||
|
|
@@ -52,6 +53,17 @@ class tethys::ScienceSensorsSystemPrivate | |
| ////////////////////////////////// | ||
| // Functions for data manipulation | ||
|
|
||
| /// \brief Called when plugin is asked to reload file. | ||
| /// \param[in] _filepath Path to file to reload. | ||
| public: void OnReloadData(const ignition::msgs::StringMsg &_filepath) | ||
| { | ||
| igndbg << "Reloading file " << _filepath.data() << "\n"; | ||
|
|
||
| // Trigger reload and reread data | ||
| this->sphericalCoordinatesInitialized = false; | ||
| this->dataPath = _filepath.data(); | ||
| } | ||
|
|
||
| /// \brief Reads csv file and populate various data fields | ||
| /// \param[in] _ecm Immutable reference to the ECM | ||
| public: void ReadData(const ignition::gazebo::EntityComponentManager &_ecm); | ||
|
|
@@ -85,6 +97,11 @@ class tethys::ScienceSensorsSystemPrivate | |
| /// \brief Returns a point cloud message populated with the latest sensor data | ||
| public: ignition::msgs::PointCloudPacked PointCloudMsg(); | ||
|
|
||
| public: float InterpolateInTime( | ||
| const ignition::math::Vector3d &_point, | ||
| const double simTimeSeconds, | ||
| const std::vector<std::vector<float>> &_dataArray); | ||
|
|
||
| /////////////////////////////// | ||
| // Constants for data manipulation | ||
|
|
||
|
|
@@ -156,11 +173,8 @@ class tethys::ScienceSensorsSystemPrivate | |
| ////////////////////////////////// | ||
| // Variables for data manipulation | ||
|
|
||
| /// \brief Whether using more than one time slices of data | ||
| public: bool multipleTimeSlices {false}; | ||
|
|
||
| /// \brief Index of the latest time slice | ||
| public: int timeIdx {0}; | ||
| public: std::size_t timeIdx {0}; | ||
|
|
||
| /// \brief Timestamps to index slices of data | ||
| public: std::vector<float> timestamps; | ||
|
|
@@ -174,7 +188,7 @@ class tethys::ScienceSensorsSystemPrivate | |
| /// the visuallization. | ||
| public: std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> timeSpaceCoords; | ||
|
|
||
| public: std::vector<std::vector<ignition::math::Vector3d>> | ||
| public: std::vector<std::vector<ignition::math::Vector3d>> | ||
| timeSpaceCoordsLatLon; | ||
|
|
||
| /// \brief Spatial index of data. | ||
|
|
@@ -302,6 +316,63 @@ ScienceSensorsSystem::ScienceSensorsSystem() | |
| { | ||
| } | ||
|
|
||
| ///////////////////////////////////////////////// | ||
| float ScienceSensorsSystemPrivate::InterpolateInTime( | ||
| const ignition::math::Vector3d &_point, | ||
| const double _simTimeSeconds, | ||
| const std::vector<std::vector<float>> &_dataArray) | ||
| { | ||
| const auto& timeslice1 = this->timeSpaceIndex[this->timeIdx]; | ||
| auto interpolatorsTime1 = timeslice1.GetInterpolators(_point); | ||
|
|
||
| auto nextTimeIdx = std::min(this->timeIdx + 1, | ||
| this->timestamps.size() - 1); | ||
| const auto& timeslice2 = this->timeSpaceIndex[nextTimeIdx]; | ||
| auto interpolatorsTime2 = timeslice2.GetInterpolators(_point); | ||
|
|
||
| if (interpolatorsTime1.size() == 0) return std::nanf(""); | ||
| if (!interpolatorsTime1[0].index.has_value()) return std::nanf(""); | ||
|
|
||
| if (interpolatorsTime2.size() == 0) return std::nanf(""); | ||
| if (!interpolatorsTime2[0].index.has_value()) return std::nanf(""); | ||
|
|
||
| const auto data1 = timeslice1.EstimateValueUsingTrilinear( | ||
| interpolatorsTime1, | ||
| _point, | ||
| _dataArray[this->timeIdx] | ||
| ); | ||
| const auto data2 = timeslice2.EstimateValueUsingTrilinear( | ||
arjo129 marked this conversation as resolved.
Show resolved
Hide resolved
|
||
| interpolatorsTime2, | ||
| _point, | ||
| _dataArray[nextTimeIdx] | ||
| ); | ||
|
|
||
|
|
||
| auto prevTimeStamp = this->timestamps[this->timeIdx]; | ||
| auto nextTimeStamp = this->timestamps[nextTimeIdx]; | ||
|
|
||
| auto dist = nextTimeStamp - prevTimeStamp; | ||
| if (dist == 0) | ||
arjo129 marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| { | ||
| if (data1.has_value()) | ||
arjo129 marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| return data1.value(); | ||
| else | ||
| return std::nanf(""); | ||
| } | ||
| else | ||
| { | ||
| if (data1.has_value() && data2.has_value()) | ||
| { | ||
| return (data1.value() * (nextTimeStamp - _simTimeSeconds) + | ||
| data2.value() * (_simTimeSeconds - prevTimeStamp)) / dist; | ||
| } | ||
| else | ||
| { | ||
| return std::nanf(""); | ||
| } | ||
| } | ||
| } | ||
|
|
||
| ///////////////////////////////////////////////// | ||
| void ScienceSensorsSystemPrivate::ReadData( | ||
| const ignition::gazebo::EntityComponentManager &_ecm) | ||
|
|
@@ -319,6 +390,16 @@ void ScienceSensorsSystemPrivate::ReadData( | |
| // reading and transforming data | ||
| std::lock_guard<std::mutex> lock(mtx); | ||
|
|
||
| // Reset all data | ||
| timeSpaceCoords.clear(); | ||
| timeSpaceCoordsLatLon.clear(); | ||
| timeSpaceIndex.clear(); | ||
| temperatureArr.clear(); | ||
| salinityArr.clear(); | ||
| chlorophyllArr.clear(); | ||
| eastCurrentArr.clear(); | ||
| northCurrentArr.clear(); | ||
|
|
||
| std::fstream fs; | ||
| fs.open(this->dataPath, std::ios::in); | ||
|
|
||
|
|
@@ -552,6 +633,10 @@ void ScienceSensorsSystem::Configure( | |
| ignmsg << "Loading science data from [" << this->dataPtr->dataPath << "]" | ||
| << std::endl; | ||
| } | ||
|
|
||
| this->dataPtr->node.Subscribe("/world/science_sensor/environment_data_path", | ||
| &ScienceSensorsSystemPrivate::OnReloadData, | ||
| this->dataPtr.get()); | ||
| } | ||
|
|
||
| ///////////////////////////////////////////////// | ||
|
|
@@ -635,21 +720,14 @@ void ScienceSensorsSystem::PostUpdate(const ignition::gazebo::UpdateInfo &_info, | |
| } | ||
| } | ||
|
|
||
| double simTimeSeconds = std::chrono::duration_cast<std::chrono::seconds>( | ||
| double simTimeSeconds = std::chrono::duration<double>( | ||
| _info.simTime).count(); | ||
|
|
||
| // Update time index | ||
| if (this->dataPtr->multipleTimeSlices) | ||
| if(this->dataPtr->timeIdx + 1 < this->dataPtr->timestamps.size()) | ||
| { | ||
| // Only update if sim time exceeds the elapsed timestamp in data | ||
| if (!this->dataPtr->timestamps.empty() && | ||
| simTimeSeconds >= this->dataPtr->timestamps[this->dataPtr->timeIdx]) | ||
| if(simTimeSeconds >= this->dataPtr->timestamps[this->dataPtr->timeIdx + 1]) | ||
| { | ||
| // Increment for next point in time | ||
| this->dataPtr->timeIdx++; | ||
|
|
||
| // Publish science data at the next timestamp | ||
| this->dataPtr->PublishData(); | ||
| } | ||
| } | ||
|
|
||
|
|
@@ -680,97 +758,42 @@ void ScienceSensorsSystem::PostUpdate(const ignition::gazebo::UpdateInfo &_info, | |
| auto sphericalDepthCorrected = ignition::math::Vector3d{spherical.X(), spherical.Y(), | ||
| -spherical.Z()}; | ||
|
|
||
| const auto& timeslice = this->dataPtr->timeSpaceIndex[this->dataPtr->timeIdx]; | ||
| auto interpolators = timeslice.GetInterpolators(sphericalDepthCorrected); | ||
|
|
||
| IGN_PROFILE("ScienceSensorsSystem::Interpolation"); | ||
| if (interpolators.size() == 0) return; | ||
| if (!interpolators[0].index.has_value()) return; | ||
|
|
||
| if (auto casted = std::dynamic_pointer_cast<SalinitySensor>(sensor)) | ||
| { | ||
| const auto sal = timeslice.EstimateValueUsingTrilinear( | ||
| interpolators, | ||
| sphericalDepthCorrected, | ||
| this->dataPtr->salinityArr[this->dataPtr->timeIdx] | ||
| ); | ||
|
|
||
| if (sal.has_value()) | ||
| casted->SetData(sal.value()); | ||
| else | ||
| casted->SetData(std::nanf("")); | ||
| casted->SetData( | ||
| this->dataPtr->InterpolateInTime( | ||
| sphericalDepthCorrected, simTimeSeconds, this->dataPtr->salinityArr)); | ||
| } | ||
| else if (auto casted = std::dynamic_pointer_cast<TemperatureSensor>( | ||
| sensor)) | ||
| { | ||
| const auto temp = timeslice.EstimateValueUsingTrilinear( | ||
| interpolators, | ||
| sphericalDepthCorrected, | ||
| this->dataPtr->temperatureArr[this->dataPtr->timeIdx] | ||
| ); | ||
| const auto temp = this->dataPtr->InterpolateInTime( | ||
| sphericalDepthCorrected, simTimeSeconds, this->dataPtr->temperatureArr); | ||
|
|
||
| if (temp.has_value()) | ||
| { | ||
| ignition::math::Temperature tempC; | ||
| tempC.SetCelsius(temp.value()); | ||
| casted->SetData(tempC); | ||
| } | ||
| else | ||
| { | ||
| ignition::math::Temperature tempC; | ||
| tempC.SetCelsius(std::nanf("")); | ||
| casted->SetData(tempC); | ||
| } | ||
| ignition::math::Temperature tempC; | ||
| tempC.SetCelsius(temp); | ||
| casted->SetData(tempC); | ||
| } | ||
| else if (auto casted = std::dynamic_pointer_cast<ChlorophyllSensor>( | ||
| sensor)) | ||
| { | ||
| /// Uncomment to debug | ||
| /// igndbg << "------------------" << std::endl; | ||
| /// igndbg << "Sensor position: " << sphericalDepthCorrected << std::endl; | ||
| /// igndbg << "Got" << interpolators.size() << " interpolators" << std::endl; | ||
| /// for (auto interp: interpolators) | ||
| /// { | ||
| /// if (!interp.index.has_value()) continue; | ||
| /// igndbg << "Chlorophyll sensor: " << | ||
| /// this->dataPtr->chlorophyllArr[this->dataPtr->timeIdx][ | ||
| /// interp.index.value()] << "@" << interp.position << std::endl; | ||
| /// igndbg << "My distance is " << interp.position.X() - sphericalDepthCorrected.X() | ||
| /// << ", " << interp.position.Y() - sphericalDepthCorrected.Y() << std::endl; | ||
| /// } | ||
| const auto chlor = timeslice.EstimateValueUsingTrilinear( | ||
| interpolators, | ||
| sphericalDepthCorrected, | ||
| this->dataPtr->chlorophyllArr[this->dataPtr->timeIdx] | ||
| ); | ||
| if (chlor.has_value()) | ||
| casted->SetData(chlor.value()); | ||
| else | ||
| casted->SetData(std::nanf("")); | ||
| casted->SetData( | ||
| this->dataPtr->InterpolateInTime( | ||
| sphericalDepthCorrected, simTimeSeconds, | ||
| this->dataPtr->chlorophyllArr)); | ||
| } | ||
| else if (auto casted = std::dynamic_pointer_cast<CurrentSensor>( | ||
| sensor)) | ||
| { | ||
| const auto nCurr = timeslice.EstimateValueUsingTrilinear( | ||
| interpolators, | ||
| sphericalDepthCorrected, | ||
| this->dataPtr->northCurrentArr[this->dataPtr->timeIdx] | ||
| ); | ||
| const auto eCurr = timeslice.EstimateValueUsingTrilinear( | ||
| interpolators, | ||
| sphericalDepthCorrected, | ||
| this->dataPtr->eastCurrentArr[this->dataPtr->timeIdx] | ||
| ); | ||
| if (nCurr.has_value() && eCurr.has_value()) | ||
| { | ||
| ignition::math::Vector3d current(nCurr.value(), eCurr.value(), 0); | ||
| casted->SetData(current); | ||
| } | ||
| else | ||
| { | ||
| ignition::math::Vector3d current(std::nan(""), std::nan(""), 0); | ||
| casted->SetData(current); | ||
| } | ||
| const auto nCurr = this->dataPtr->InterpolateInTime( | ||
| sphericalDepthCorrected, simTimeSeconds, this->dataPtr->northCurrentArr); | ||
|
|
||
| const auto eCurr = this->dataPtr->InterpolateInTime( | ||
| sphericalDepthCorrected, simTimeSeconds, this->dataPtr->eastCurrentArr); | ||
|
|
||
|
|
||
| ignition::math::Vector3d current(nCurr, eCurr, 0); | ||
|
||
| casted->SetData(current); | ||
| } | ||
| else | ||
| { | ||
|
|
||
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,17 @@ | ||
| elapsed_time_second,latitude_degree,longitude_degree,depth_meter,sea_water_temperature_degC,sea_water_salinity_psu,mass_concentration_of_chlorophyll_in_sea_water_ugram_per_liter,eastward_sea_water_velocity_meter_per_sec,northward_sea_water_velocity_meter_per_sec | ||
| 0,0.00001,0.00000,0,5.0,0.001,0,-1,0.5 | ||
| 0,0.00001,0.00000,10,5.0,0.001,0,-1,0.5 | ||
| 0,0.00001,0.00001,0,5.0,0.001,0,-1,0.5 | ||
| 0,0.00001,0.00001,10,5.0,0.001,0,-1,0.5 | ||
| 0,0.00000,0.00000,0,5.0,0.001,0,-1,0.5 | ||
| 0,0.00000,0.00000,10,5.0,0.001,0,-1,0.5 | ||
| 0,0.00000,0.00001,0,5.0,0.001,0,-1,0.5 | ||
| 0,0.00000,0.00001,10,5.0,0.001,0,-1,0.5 | ||
| 10,0.00001,0.00000,0,10.0,0.001,0,-1,0.5 | ||
| 10,0.00001,0.00000,10,10.0,0.001,0,-1,0.5 | ||
| 10,0.00001,0.00001,0,10.0,0.001,0,-1,0.5 | ||
| 10,0.00001,0.00001,10,10.0,0.001,0,-1,0.5 | ||
| 10,0.00000,0.00000,00,10.0,0.001,0,-1,0.5 | ||
| 10,0.00000,0.00000,10,10.0,0.001,0,-1,0.5 | ||
| 10,0.00000,0.00001,0,10.0,0.001,0,-1,0.5 | ||
| 10,0.00000,0.00001,10,10.0,0.001,0,-1,0.5 |
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
Uh oh!
There was an error while loading. Please reload this page.