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

Add support for loading CSV files via the UI #211

Merged
merged 6 commits into from
Jun 15, 2022
Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
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
1 change: 1 addition & 0 deletions lrauv_ignition_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -181,6 +181,7 @@ add_lrauv_plugin(TimeAnalysisPlugin)
add_lrauv_plugin(WorldCommPlugin
PROTO
lrauv_init)
add_lrauv_plugin(WorldConfigPlugin GUI)

#============================================================================
# Install public headers
Expand Down
205 changes: 114 additions & 91 deletions lrauv_ignition_plugins/src/ScienceSensorsSystem.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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>

Expand All @@ -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);
Expand Down Expand Up @@ -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

Expand Down Expand Up @@ -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;
Expand All @@ -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.
Expand Down Expand Up @@ -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(
interpolatorsTime2,
_point,
_dataArray[nextTimeIdx]
);


auto prevTimeStamp = this->timestamps[this->timeIdx];
auto nextTimeStamp = this->timestamps[nextTimeIdx];

auto dist = nextTimeStamp - prevTimeStamp;
if (dist == 0)
{
if (data1.has_value())
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)
Expand All @@ -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);

Expand Down Expand Up @@ -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());
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -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();
}
}

Expand Down Expand Up @@ -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
{
Expand Down
70 changes: 70 additions & 0 deletions lrauv_ignition_plugins/src/WorldConfigPlugin.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
/*
* Copyright (C) 2022 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

/*
* Development of this module has been funded by the Monterey Bay Aquarium
* Research Institute (MBARI) and the David and Lucile Packard Foundation
*/

#include "WorldConfigPlugin.hh"
#include <ignition/common/Console.hh>
#include <ignition/plugin/Register.hh>

#include <ignition/gui/Application.hh>
#include <ignition/gui/Conversions.hh>
#include <ignition/gui/GuiEvents.hh>
#include <ignition/gui/MainWindow.hh>

namespace tethys
{

WorldConfig::WorldConfig() : ignition::gui::Plugin()
{
ignition::gui::App()->Engine()->rootContext()->setContextProperty(
"WorldConfig", this);
this->pub =
this->node.Advertise<ignition::msgs::StringMsg>(
"/world/science_sensor/environment_data_path");
}

WorldConfig::~WorldConfig()
{

}

void WorldConfig::LoadConfig(const tinyxml2::XMLElement *_pluginElem)
{
if (this->title.empty())
this->title = "World Configuration";

ignition::gui::App()->findChild<
ignition::gui::MainWindow *>()->installEventFilter(this);
}

void WorldConfig::SetFilePath(QUrl _filePath)
{
igndbg << "setting file path "<< _filePath.path().toStdString() <<"\n";
arjo129 marked this conversation as resolved.
Show resolved Hide resolved

ignition::msgs::StringMsg msg;
msg.set_data(_filePath.path().toStdString());
this->pub.Publish(msg);
}

}
// Register this plugin
IGNITION_ADD_PLUGIN(tethys::WorldConfig,
ignition::gui::Plugin)
arjo129 marked this conversation as resolved.
Show resolved Hide resolved
Loading