@@ -81,9 +81,8 @@ class DirectDataPublisher : public DataFieldPublisher
81
81
* \param nh The used ROS node handle
82
82
*/
83
83
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 )
85
85
{
86
- pub_.reset (new realtime_tools::RealtimePublisher<MsgT>(nh, " rtde_data/" + data_field_identifier_, 1 ));
87
86
}
88
87
89
88
/* !
@@ -97,14 +96,11 @@ class DirectDataPublisher : public DataFieldPublisher
97
96
{
98
97
if (data_package.getData (data_field_identifier_, data_))
99
98
{
100
- if (pub_)
99
+ if (pub_. trylock () )
101
100
{
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 ;
108
104
}
109
105
}
110
106
return false ;
@@ -113,7 +109,7 @@ class DirectDataPublisher : public DataFieldPublisher
113
109
private:
114
110
DataT data_;
115
111
std::string data_field_identifier_;
116
- std::unique_ptr< realtime_tools::RealtimePublisher<MsgT> > pub_;
112
+ realtime_tools::RealtimePublisher<MsgT> pub_;
117
113
};
118
114
119
115
/* !
@@ -132,10 +128,8 @@ class ArrayDataPublisher : public DataFieldPublisher
132
128
* \param nh The used ROS node handle
133
129
*/
134
130
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 )
136
132
{
137
- pub_.reset (new realtime_tools::RealtimePublisher<MsgT>(nh, " rtde_data/" + data_field_identifier_, 1 ));
138
- pub_->msg_ .data .resize (N);
139
133
}
140
134
141
135
/* !
@@ -149,17 +143,14 @@ class ArrayDataPublisher : public DataFieldPublisher
149
143
{
150
144
if (data_package.getData (data_field_identifier_, data_))
151
145
{
152
- if (pub_)
146
+ if (pub_. trylock () )
153
147
{
154
- if (pub_-> trylock () )
148
+ for ( size_t i = 0 ; i < N; i++ )
155
149
{
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];
162
151
}
152
+ pub_.unlockAndPublish ();
153
+ return true ;
163
154
}
164
155
}
165
156
return false ;
@@ -168,7 +159,7 @@ class ArrayDataPublisher : public DataFieldPublisher
168
159
private:
169
160
std::array<DataT, N> data_;
170
161
std::string data_field_identifier_;
171
- std::unique_ptr< realtime_tools::RealtimePublisher<MsgT> > pub_;
162
+ realtime_tools::RealtimePublisher<MsgT> pub_;
172
163
};
173
164
} // namespace rtde_interface
174
165
} // namespace ur_driver
0 commit comments