-
Notifications
You must be signed in to change notification settings - Fork 14
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
Science data: lat/lon to cartesian #70
Changes from all commits
5ec0460
7a89db4
7ecf0e0
3dc76c7
9cc1b42
3853681
2c8f6ae
3f6edfc
98098c3
64eca32
dae526f
17a165c
6aa7076
58af8e8
b6b5245
6a5b426
d443425
00128b9
c287169
f68ec87
7bc8e98
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change | ||||||
---|---|---|---|---|---|---|---|---|
|
@@ -43,6 +43,20 @@ using namespace tethys; | |||||||
|
||||||||
class tethys::ScienceSensorsSystemPrivate | ||||||||
{ | ||||||||
/// \brief Initialize world origin in spherical coordinates | ||||||||
public: void UpdateWorldSphericalOrigin( | ||||||||
ignition::gazebo::EntityComponentManager &_ecm); | ||||||||
|
||||||||
/// \brief Convert (lat, lon, 0) to Cartesian XYZ, including shifting by | ||||||||
/// world origin | ||||||||
public: void ConvertLatLonToCart( | ||||||||
const ignition::math::Vector3d &_latLonEle, | ||||||||
ignition::math::Vector3d &_cart); | ||||||||
|
||||||||
/// \brief Shift point cloud with respect to the world origin in spherical | ||||||||
/// coordinates, if available. | ||||||||
public: void ShiftDataToNewSphericalOrigin(); | ||||||||
|
||||||||
/// \brief Reads csv file and populate various data fields | ||||||||
public: void ReadData(); | ||||||||
|
||||||||
|
@@ -107,9 +121,29 @@ class tethys::ScienceSensorsSystemPrivate | |||||||
/// \brief Indicates whether data has been loaded | ||||||||
public: bool initialized {false}; | ||||||||
|
||||||||
/// \brief Set to true after the spherical coordinates have been initialized. | ||||||||
/// This may happen at startup if the SDF file has them hardcoded, or at | ||||||||
/// runtime when the first vehicle is spawned. Assume the coordinates are | ||||||||
/// only shifted once. | ||||||||
public: bool worldSphericalCoordsInitialized {false}; | ||||||||
|
||||||||
/// \brief Mutex for writing to world origin association to lat/long | ||||||||
public: std::mutex mtx; | ||||||||
|
||||||||
/// \brief Spherical coordinates of world origin. Can change at any time. | ||||||||
public: ignition::math::SphericalCoordinates worldOriginSphericalCoords; | ||||||||
|
||||||||
/// \brief World origin in spherical position (latitude, longitude, | ||||||||
/// elevation), angles in degrees | ||||||||
public: ignition::math::Vector3d worldOriginSphericalPos = {0, 0, 0}; | ||||||||
|
||||||||
/// \brief World origin in Cartesian coordinates converted from spherical | ||||||||
/// coordinates | ||||||||
public: ignition::math::Vector3d worldOriginCartesianCoords = {0, 0, 0}; | ||||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I don't understand this variable. Isn't the world origin in Cartesian always zero? What does a non-zero cartesian origin mean? |
||||||||
|
||||||||
/// \brief For conversions | ||||||||
public: ignition::math::SphericalCoordinates sphCoord; | ||||||||
|
||||||||
/// \brief Whether using more than one time slices of data | ||||||||
public: bool multipleTimeSlices {false}; | ||||||||
|
||||||||
|
@@ -190,9 +224,9 @@ class tethys::ScienceSensorsSystemPrivate | |||||||
// For 2003080103_mb_l3_las_1x1km.csv | ||||||||
//public: const float MINIATURE_SCALE = 0.01; | ||||||||
// For 2003080103_mb_l3_las.csv | ||||||||
//public: const float MINIATURE_SCALE = 0.0001; | ||||||||
public: const float MINIATURE_SCALE = 0.0001; | ||||||||
// For simple_test.csv | ||||||||
public: const float MINIATURE_SCALE = 1000.0; | ||||||||
// public: const float MINIATURE_SCALE = 1000.0; | ||||||||
|
||||||||
// TODO This is a workaround pending upstream Marker performance improvements. | ||||||||
// \brief Performance trick. Skip depths below this z, so have memory to | ||||||||
|
@@ -437,8 +471,9 @@ void ScienceSensorsSystemPrivate::ReadData() | |||||||
continue; | ||||||||
} | ||||||||
|
||||||||
// TODO: Convert spherical coordinates to Cartesian | ||||||||
ignition::math::Vector3d cart = {latitude, longitude, -depth}; | ||||||||
// Convert spherical coordinates to Cartesian | ||||||||
ignition::math::Vector3d cart; | ||||||||
this->ConvertLatLonToCart({latitude, longitude, -depth}, cart); | ||||||||
|
||||||||
// Performance trick. Scale down to see in view | ||||||||
cart *= this->MINIATURE_SCALE; | ||||||||
|
@@ -453,6 +488,7 @@ void ScienceSensorsSystemPrivate::ReadData() | |||||||
|
||||||||
// Gather spatial coordinates, 3 fields in the line, into point cloud | ||||||||
// for indexing this time slice of data. | ||||||||
// Flip sign of z, because positive depth is negative z. | ||||||||
this->timeSpaceCoords[lineTimeIdx]->push_back( | ||||||||
pcl::PointXYZ(cart.X(), cart.Y(), cart.Z())); | ||||||||
|
||||||||
|
@@ -487,6 +523,93 @@ void ScienceSensorsSystemPrivate::ReadData() | |||||||
this->initialized = true; | ||||||||
} | ||||||||
|
||||||||
///////////////////////////////////////////////// | ||||||||
void ScienceSensorsSystemPrivate::UpdateWorldSphericalOrigin( | ||||||||
ignition::gazebo::EntityComponentManager &_ecm) | ||||||||
{ | ||||||||
// Lock for changes to worldOriginSpherical* until update complete | ||||||||
std::lock_guard<std::mutex> lock(mtx); | ||||||||
|
||||||||
// Data positions have not been transformed wrt world origin lat/long | ||||||||
if (!this->worldSphericalCoordsInitialized) | ||||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Nitpick: In situations like this, it looks a bit cleaner if you return early on the opposite condition. It's easier to read the code if we know that the function ends here, and also reduces indentation of the block below.
Suggested change
I think we can lock the mutex after this block? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Actually, we cannot return right away. That's actually a logic error due to incorrect braces. Thanks for catching that. The if-statement is there because That hadn't been caught because There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I pulled the function call out of the if-statement (to be committed, will post hash), but the logic might need to be changed once the function is coded. The logic is a combination of Really, I just put the calls in there for whoever that implements There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. TODOs added in c287169 |
||||||||
{ | ||||||||
auto latLon = this->world.SphericalCoordinates(_ecm); | ||||||||
if (latLon) | ||||||||
{ | ||||||||
ignwarn << "New spherical coordinates detected: " | ||||||||
<< latLon.value().LatitudeReference().Degree() << ", " | ||||||||
<< latLon.value().LongitudeReference().Degree() << std::endl; | ||||||||
|
||||||||
this->worldOriginSphericalCoords = latLon.value(); | ||||||||
|
||||||||
// Extract world origin in (lat, long, elevation) from spherical coords | ||||||||
this->worldOriginSphericalPos = ignition::math::Vector3d( | ||||||||
this->worldOriginSphericalCoords.LatitudeReference().Degree(), | ||||||||
this->worldOriginSphericalCoords.LongitudeReference().Degree(), | ||||||||
// TODO look into why converting with elevation don't give depth as z | ||||||||
// Details https://github.com/osrf/lrauv/pull/70#discussion_r755679895 | ||||||||
//this->worldOriginSphericalCoords.ElevationReference()); | ||||||||
0); | ||||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Any reason to hardcode
Suggested change
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. There's something weird about the conversion. I don't know if it's because I'm using the function wrong, or we're not using Z the way the function assumes. The depth conversion result looks wrong if I give it the actual elevation, in that it doesn't give us Short of a fix, I can add a TODO linking to this comment. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. TODO added in c287169 There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. How can I reproduce the failure? I see |
||||||||
// Convert spherical coordinates to Cartesian | ||||||||
this->sphCoord = ignition::math::SphericalCoordinates( | ||||||||
this->worldOriginSphericalCoords.Surface()); | ||||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. It's not clear to me what's the intended difference between
Are they supposed to be different? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. They gave me different results. I don't know why, but I had to create a new one for the markers to be at reasonable places. The difference is that I tried it again with this fix in both places in the code, mentioned here #70 (comment) , and the former is still giving positions like this:
I will say at the time this was coded, I just needed something, anything, to show up at the origin, so a quick hack was needed. So while Here's what I would propose. Right now, since #83 is pending on this, I would propose to delay the fix again, so that #83 isn't blocked. I know that's not good, but I also suspect after #83 and another PR to do the interpolation, then we can actually test the sensor locations and maybe figure out why this is wrong. Very honestly, right now, there is still realistically nothing to test this code. We see some colors, but we really have no idea whether they're correct wrt neither lat/long nor Cartesian! So all of these PRs are just code that won't be tested until a few weeks later (but hopefully much much sooner, like before end of month fingers crossed), when we run the MBARI acceptance mission. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. TODO added in c287169 There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
I'm ok fixing this incrementally, my only concern is that the positions could be completely wrong right now. Would that affect how #83 is implemented?
I think we can come up with some tests, we just need to create some dummy data that we know exactly where it should go. In fact, I think we should be working against this kind of data before we try to load the real datasets, because it's much easier to create different scenarios to test. My suggestion would be to add more datapoints to dummy.csv and check that they behave as expected. I'll do that now locally here to help me wrap my head around this PR. |
||||||||
this->worldOriginCartesianCoords = | ||||||||
// TODO look into why converting with worldOriginSphericalCoords gives | ||||||||
// unexpected positions. | ||||||||
// Details https://github.com/osrf/lrauv/pull/70#discussion_r755681564 | ||||||||
//this->worldOriginSphericalCoords.LocalFromSphericalPosition( | ||||||||
this->sphCoord.LocalFromSphericalPosition( | ||||||||
this->worldOriginSphericalPos); | ||||||||
|
||||||||
igndbg << "Data will be transformed wrt world origin in Cartesian (" | ||||||||
<< this->worldOriginCartesianCoords.X() << ", " | ||||||||
<< this->worldOriginCartesianCoords.Y() << ", " | ||||||||
<< this->worldOriginCartesianCoords.Z() << ")" << std::endl; | ||||||||
|
||||||||
this->worldSphericalCoordsInitialized = true; | ||||||||
} | ||||||||
} | ||||||||
|
||||||||
// TODO(chapulina) Shift science data to new coordinates. This logic might | ||||||||
// need to be updated. | ||||||||
// If data had been loaded before origin was updated, need to shift data | ||||||||
if (this->initialized) | ||||||||
{ | ||||||||
this->ShiftDataToNewSphericalOrigin(); | ||||||||
} | ||||||||
} | ||||||||
|
||||||||
///////////////////////////////////////////////// | ||||||||
void ScienceSensorsSystemPrivate::ConvertLatLonToCart( | ||||||||
const ignition::math::Vector3d &_latLonEle, | ||||||||
ignition::math::Vector3d &_cart) | ||||||||
{ | ||||||||
// Convert spherical coordinates to Cartesian | ||||||||
_cart = this->sphCoord.LocalFromSphericalPosition( | ||||||||
ignition::math::Vector3d(_latLonEle.X(), _latLonEle.Y(), 0)); | ||||||||
|
||||||||
// Shift to be relative to world origin spherical coordinates | ||||||||
_cart -= this->worldOriginCartesianCoords; | ||||||||
|
||||||||
// Set depth | ||||||||
_cart.Z() = _latLonEle.Z(); | ||||||||
|
||||||||
/* | ||||||||
igndbg << "Data point at Cartesian (" | ||||||||
<< _cart.X() << ", " | ||||||||
<< _cart.Y() << ", " | ||||||||
<< _cart.Z() << ")" << std::endl; | ||||||||
*/ | ||||||||
} | ||||||||
|
||||||||
///////////////////////////////////////////////// | ||||||||
void ScienceSensorsSystemPrivate::ShiftDataToNewSphericalOrigin() | ||||||||
{ | ||||||||
// Lock modifications to world origin spherical association until finish | ||||||||
// transforming data | ||||||||
std::lock_guard<std::mutex> lock(mtx); | ||||||||
} | ||||||||
|
||||||||
///////////////////////////////////////////////// | ||||||||
void ScienceSensorsSystemPrivate::GenerateOctrees() | ||||||||
{ | ||||||||
|
@@ -602,6 +725,10 @@ void ScienceSensorsSystem::Configure( | |||||||
this->dataPtr->salPub = this->dataPtr->node.Advertise< | ||||||||
ignition::msgs::Float_V>("/salinity"); | ||||||||
|
||||||||
// Initialize world origin in spherical coordinates, so data is loaded to the | ||||||||
// correct Cartesian positions. | ||||||||
this->dataPtr->UpdateWorldSphericalOrigin(_ecm); | ||||||||
|
||||||||
this->dataPtr->ReadData(); | ||||||||
this->dataPtr->GenerateOctrees(); | ||||||||
|
||||||||
|
@@ -614,6 +741,12 @@ void ScienceSensorsSystem::PreUpdate( | |||||||
const ignition::gazebo::UpdateInfo &, | ||||||||
ignition::gazebo::EntityComponentManager &_ecm) | ||||||||
{ | ||||||||
// TODO: Test this logic once ShiftDataToNewSphericalOrigin() is implemented | ||||||||
if (!this->dataPtr->worldSphericalCoordsInitialized) | ||||||||
{ | ||||||||
this->dataPtr->UpdateWorldSphericalOrigin(_ecm); | ||||||||
} | ||||||||
|
||||||||
_ecm.EachNew<ignition::gazebo::components::CustomSensor, | ||||||||
ignition::gazebo::components::ParentEntity>( | ||||||||
[&](const ignition::gazebo::Entity &_entity, | ||||||||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Do we need to store this variable? I don't see it being used anywhere besides right after it is set.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I print this out in
ReadData()
in #83. That might be another forward-merge thing. I think this is a useful variable that I'll be using for debugging until all the sensor stuff is finalized. We're still pretty far from that, at least 2 more PRs, before actually testing the missions, which will probably be 1 more PR.There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I think it's just holding duplicate data that's already in
worldOriginSphericalCoords
, right? Couldn't you just print the values from that? Keeping the same information in 2 places is prone to error because we need to keep them in sync.