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

Lock ocean current calculation function #213

Merged
merged 3 commits into from
Feb 23, 2022
Merged
Show file tree
Hide file tree
Changes from all 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
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
#include <string>
#include <vector>
#include <thread>
#include <mutex>
#include "ros/callback_queue.h"
#include "ros/subscribe_options.h"

Expand Down Expand Up @@ -108,6 +109,9 @@ namespace gazebo
/// \brief A thread the keeps running the rosQueue
private: std::thread databaseSubQueueThread;

/// \brief A thread mutex to lock
private: std::mutex lock_;

/// \brief Period after which we should publish a message via ROS.
private: gazebo::common::Time rosPublishPeriod;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -250,6 +250,8 @@ void TransientCurrentPlugin::Update(const gazebo::common::UpdateInfo &)
void TransientCurrentPlugin::UpdateDatabase(
const dave_gazebo_ros_plugins::StratifiedCurrentDatabase::ConstPtr &_msg)
{
this->lock_.lock();

this->database.clear();
for (int i = 0; i < _msg->depths.size(); i++)
{
Expand Down Expand Up @@ -299,11 +301,15 @@ void TransientCurrentPlugin::UpdateDatabase(
this->world_start_time[3] = _msg->worldStartTimeHour;
this->world_start_time[4] = _msg->worldStartTimeMinute;
}

this->lock_.unlock();
}

/////////////////////////////////////////////////
void TransientCurrentPlugin::CalculateOceanCurrent()
{
this->lock_.lock();

// Update vehicle position
double vehicleDepth = - this->model->WorldPose().Pos().Z();

Expand Down Expand Up @@ -442,6 +448,8 @@ void TransientCurrentPlugin::CalculateOceanCurrent()
// Update time stamp
this->lastUpdate = time;
}

this->lock_.unlock();
}

/////////////////////////////////////////////////
Expand Down