Skip to content

Commit 61d7801

Browse files
authored
Merge pull request #213 from Field-Robotics-Lab/lock_stratified_current_update
Lock ocean current calculation function.
2 parents 5e2271f + 32c4955 commit 61d7801

File tree

2 files changed

+12
-0
lines changed

2 files changed

+12
-0
lines changed

gazebo/dave_gazebo_model_plugins/include/dave_gazebo_model_plugins/ocean_current_model_plugin.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,7 @@
3636
#include <string>
3737
#include <vector>
3838
#include <thread>
39+
#include <mutex>
3940
#include "ros/callback_queue.h"
4041
#include "ros/subscribe_options.h"
4142

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

112+
/// \brief A thread mutex to lock
113+
private: std::mutex lock_;
114+
111115
/// \brief Period after which we should publish a message via ROS.
112116
private: gazebo::common::Time rosPublishPeriod;
113117

gazebo/dave_gazebo_model_plugins/src/ocean_current_model_plugin.cc

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -250,6 +250,8 @@ void TransientCurrentPlugin::Update(const gazebo::common::UpdateInfo &)
250250
void TransientCurrentPlugin::UpdateDatabase(
251251
const dave_gazebo_ros_plugins::StratifiedCurrentDatabase::ConstPtr &_msg)
252252
{
253+
this->lock_.lock();
254+
253255
this->database.clear();
254256
for (int i = 0; i < _msg->depths.size(); i++)
255257
{
@@ -299,11 +301,15 @@ void TransientCurrentPlugin::UpdateDatabase(
299301
this->world_start_time[3] = _msg->worldStartTimeHour;
300302
this->world_start_time[4] = _msg->worldStartTimeMinute;
301303
}
304+
305+
this->lock_.unlock();
302306
}
303307

304308
/////////////////////////////////////////////////
305309
void TransientCurrentPlugin::CalculateOceanCurrent()
306310
{
311+
this->lock_.lock();
312+
307313
// Update vehicle position
308314
double vehicleDepth = - this->model->WorldPose().Pos().Z();
309315

@@ -442,6 +448,8 @@ void TransientCurrentPlugin::CalculateOceanCurrent()
442448
// Update time stamp
443449
this->lastUpdate = time;
444450
}
451+
452+
this->lock_.unlock();
445453
}
446454

447455
/////////////////////////////////////////////////

0 commit comments

Comments
 (0)