Skip to content

Commit

Permalink
Use upstream's PointCloud GUI plugin (#139)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina authored Jan 26, 2022
1 parent fd93e56 commit babce6a
Show file tree
Hide file tree
Showing 8 changed files with 102 additions and 1,001 deletions.
1 change: 0 additions & 1 deletion lrauv_ignition_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -187,7 +187,6 @@ add_lrauv_plugin(TethysCommPlugin
lrauv_command
lrauv_state)
add_lrauv_plugin(TimeAnalysisPlugin)
add_lrauv_plugin(VisualizePointCloud GUI)
add_lrauv_plugin(WorldCommPlugin
PROTO
lrauv_init)
Expand Down
36 changes: 22 additions & 14 deletions lrauv_ignition_plugins/src/ScienceSensorsSystem.cc
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,9 @@ using namespace tethys;

class tethys::ScienceSensorsSystemPrivate
{
/// \brief Advertise topics and services.
public: void StartTransport();

//////////////////////////////////
// Functions for data manipulation

Expand Down Expand Up @@ -1019,32 +1022,36 @@ void ScienceSensorsSystem::Configure(
ignmsg << "Loading science data from [" << this->dataPtr->dataPath << "]"
<< std::endl;
}
}

/////////////////////////////////////////////////
void ScienceSensorsSystemPrivate::StartTransport()
{
// Advertise cloud as a service for requests on-demand, and a topic for updates
this->dataPtr->cloudPub = this->dataPtr->node.Advertise<
ignition::msgs::PointCloudPacked>(this->dataPtr->cloudTopic);
this->cloudPub = this->node.Advertise<
ignition::msgs::PointCloudPacked>(this->cloudTopic);

this->dataPtr->node.Advertise(this->dataPtr->cloudTopic,
&ScienceSensorsSystemPrivate::PointCloudService, this->dataPtr.get());
this->node.Advertise(this->cloudTopic,
&ScienceSensorsSystemPrivate::PointCloudService, this);

// Advertise science data, also as service and topics
std::string temperatureTopic{"/temperature"};
this->dataPtr->tempPub = this->dataPtr->node.Advertise<
this->tempPub = this->node.Advertise<
ignition::msgs::Float_V>(temperatureTopic);
this->dataPtr->node.Advertise(temperatureTopic,
&ScienceSensorsSystemPrivate::TemperatureService, this->dataPtr.get());
this->node.Advertise(temperatureTopic,
&ScienceSensorsSystemPrivate::TemperatureService, this);

std::string chlorophyllTopic{"/chloropyll"};
this->dataPtr->chlorPub = this->dataPtr->node.Advertise<
this->chlorPub = this->node.Advertise<
ignition::msgs::Float_V>(chlorophyllTopic);
this->dataPtr->node.Advertise(chlorophyllTopic,
&ScienceSensorsSystemPrivate::ChlorophyllService, this->dataPtr.get());
this->node.Advertise(chlorophyllTopic,
&ScienceSensorsSystemPrivate::ChlorophyllService, this);

std::string salinityTopic{"/salinity"};
this->dataPtr->salPub = this->dataPtr->node.Advertise<
this->salPub = this->node.Advertise<
ignition::msgs::Float_V>(salinityTopic);
this->dataPtr->node.Advertise(salinityTopic,
&ScienceSensorsSystemPrivate::SalinityService, this->dataPtr.get());
this->node.Advertise(salinityTopic,
&ScienceSensorsSystemPrivate::SalinityService, this);
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -1086,6 +1093,7 @@ void ScienceSensorsSystem::PostUpdate(const ignition::gazebo::UpdateInfo &_info,
{
this->dataPtr->sphericalCoordinatesInitialized = true;

this->dataPtr->StartTransport();
this->dataPtr->ReadData(_ecm);
this->dataPtr->GenerateOctrees();
}
Expand Down Expand Up @@ -1116,7 +1124,7 @@ void ScienceSensorsSystem::PostUpdate(const ignition::gazebo::UpdateInfo &_info,
}
}

// Publish every n iters so that VisualizePointCloud plugin gets it.
// Publish every n iters so that GUI PointCloud plugin gets it.
// Otherwise the initial publication in Configure() is not enough.
if (this->dataPtr->repeatPubTimes % 10000 == 0)
{
Expand Down
Loading

0 comments on commit babce6a

Please sign in to comment.