Skip to content

Commit 296b42b

Browse files
committed
Changed realtime publisher from unique_ptr to direct member
1 parent 806576b commit 296b42b

File tree

1 file changed

+13
-22
lines changed

1 file changed

+13
-22
lines changed

Diff for: ur_robot_driver/include/ur_robot_driver/ros/data_field_publisher.h

+13-22
Original file line numberDiff line numberDiff line change
@@ -81,9 +81,8 @@ class DirectDataPublisher : public DataFieldPublisher
8181
* \param nh The used ROS node handle
8282
*/
8383
DirectDataPublisher(const std::string& data_field_identifier, ros::NodeHandle& nh)
84-
: data_field_identifier_(data_field_identifier)
84+
: data_field_identifier_(data_field_identifier), pub_(nh, "rtde_data/" + data_field_identifier_, 1)
8585
{
86-
pub_.reset(new realtime_tools::RealtimePublisher<MsgT>(nh, "rtde_data/" + data_field_identifier_, 1));
8786
}
8887

8988
/*!
@@ -97,14 +96,11 @@ class DirectDataPublisher : public DataFieldPublisher
9796
{
9897
if (data_package.getData(data_field_identifier_, data_))
9998
{
100-
if (pub_)
99+
if (pub_.trylock())
101100
{
102-
if (pub_->trylock())
103-
{
104-
pub_->msg_.data = data_;
105-
pub_->unlockAndPublish();
106-
return true;
107-
}
101+
pub_.msg_.data = data_;
102+
pub_.unlockAndPublish();
103+
return true;
108104
}
109105
}
110106
return false;
@@ -113,7 +109,7 @@ class DirectDataPublisher : public DataFieldPublisher
113109
private:
114110
DataT data_;
115111
std::string data_field_identifier_;
116-
std::unique_ptr<realtime_tools::RealtimePublisher<MsgT>> pub_;
112+
realtime_tools::RealtimePublisher<MsgT> pub_;
117113
};
118114

119115
/*!
@@ -132,10 +128,8 @@ class ArrayDataPublisher : public DataFieldPublisher
132128
* \param nh The used ROS node handle
133129
*/
134130
ArrayDataPublisher(const std::string& data_field_identifier, ros::NodeHandle& nh)
135-
: data_field_identifier_(data_field_identifier)
131+
: data_field_identifier_(data_field_identifier), pub_(nh, "rtde_data/" + data_field_identifier_, 1)
136132
{
137-
pub_.reset(new realtime_tools::RealtimePublisher<MsgT>(nh, "rtde_data/" + data_field_identifier_, 1));
138-
pub_->msg_.data.resize(N);
139133
}
140134

141135
/*!
@@ -149,17 +143,14 @@ class ArrayDataPublisher : public DataFieldPublisher
149143
{
150144
if (data_package.getData(data_field_identifier_, data_))
151145
{
152-
if (pub_)
146+
if (pub_.trylock())
153147
{
154-
if (pub_->trylock())
148+
for (size_t i = 0; i < N; i++)
155149
{
156-
for (size_t i = 0; i < N; i++)
157-
{
158-
pub_->msg_.data[i] = data_[i];
159-
}
160-
pub_->unlockAndPublish();
161-
return true;
150+
pub_.msg_.data[i] = data_[i];
162151
}
152+
pub_.unlockAndPublish();
153+
return true;
163154
}
164155
}
165156
return false;
@@ -168,7 +159,7 @@ class ArrayDataPublisher : public DataFieldPublisher
168159
private:
169160
std::array<DataT, N> data_;
170161
std::string data_field_identifier_;
171-
std::unique_ptr<realtime_tools::RealtimePublisher<MsgT>> pub_;
162+
realtime_tools::RealtimePublisher<MsgT> pub_;
172163
};
173164
} // namespace rtde_interface
174165
} // namespace ur_driver

0 commit comments

Comments
 (0)