@@ -113,6 +113,23 @@ init(HardwareInterface* hw, ros::NodeHandle& nh)
113
113
m_target_wrench.setZero ();
114
114
m_ft_sensor_wrench.setZero ();
115
115
116
+ // Controller-internal state publishing
117
+ m_feedback_gravity_wrench_publisher =
118
+ std::make_shared<realtime_tools::RealtimePublisher<geometry_msgs::WrenchStamped> >(
119
+ nh, " current_gravity_wrench" , 3 );
120
+
121
+ m_feedback_sensor_wrench_publisher =
122
+ std::make_shared<realtime_tools::RealtimePublisher<geometry_msgs::WrenchStamped> >(
123
+ nh, " current_sensor_wrench" , 3 );
124
+
125
+ m_feedback_target_wrench_publisher =
126
+ std::make_shared<realtime_tools::RealtimePublisher<geometry_msgs::WrenchStamped> >(
127
+ nh, " current_target_wrench" , 3 );
128
+
129
+ m_feedback_net_force_wrench_publisher =
130
+ std::make_shared<realtime_tools::RealtimePublisher<geometry_msgs::WrenchStamped> >(
131
+ nh, " current_net_force_wrench" , 3 );
132
+
116
133
// Connect dynamic reconfigure and overwrite the default values with values
117
134
// on the parameter server. This is done automatically if parameters with
118
135
// the according names exist.
@@ -185,10 +202,28 @@ computeForceError()
185
202
target_wrench = m_target_wrench;
186
203
}
187
204
205
+ ctrl::Vector6D sensor_wrench;
206
+ sensor_wrench = Base::displayInBaseLink (m_ft_sensor_wrench,m_new_ft_sensor_ref);
207
+
208
+ ctrl::Vector6D gravity_wrench;
209
+ gravity_wrench = compensateGravity ();
210
+
188
211
// Superimpose target wrench and sensor wrench in base frame
189
- return Base::displayInBaseLink (m_ft_sensor_wrench,m_new_ft_sensor_ref)
212
+ ctrl::Vector6D net_force_wrench;
213
+ net_force_wrench = sensor_wrench
190
214
+ target_wrench
191
- + compensateGravity ();
215
+ + gravity_wrench;
216
+
217
+ // Publish wrench state feedback
218
+ if (Base::m_publish_state_feedback)
219
+ {
220
+ publishStateWrenchFeedback (m_feedback_sensor_wrench_publisher, sensor_wrench);
221
+ publishStateWrenchFeedback (m_feedback_target_wrench_publisher, target_wrench);
222
+ publishStateWrenchFeedback (m_feedback_gravity_wrench_publisher, gravity_wrench);
223
+ publishStateWrenchFeedback (m_feedback_net_force_wrench_publisher, net_force_wrench);
224
+ }
225
+
226
+ return net_force_wrench;
192
227
}
193
228
194
229
template <class HardwareInterface >
@@ -295,6 +330,25 @@ signalTaringCallback(std_srvs::Trigger::Request& req, std_srvs::Trigger::Respons
295
330
return true ;
296
331
}
297
332
333
+ template <class HardwareInterface >
334
+ void CartesianForceController<HardwareInterface>::
335
+ publishStateWrenchFeedback (realtime_tools::RealtimePublisherSharedPtr<geometry_msgs::WrenchStamped>& rt_publisher,
336
+ ctrl::Vector6D& wrench)
337
+ {
338
+ if (rt_publisher->trylock ()){
339
+ rt_publisher->msg_ .header .stamp = ros::Time::now ();
340
+ rt_publisher->msg_ .header .frame_id = Base::m_robot_base_link;
341
+ rt_publisher->msg_ .wrench .force .x = wrench[0 ];
342
+ rt_publisher->msg_ .wrench .force .y = wrench[1 ];
343
+ rt_publisher->msg_ .wrench .force .z = wrench[2 ];
344
+ rt_publisher->msg_ .wrench .torque .x = wrench[3 ];
345
+ rt_publisher->msg_ .wrench .torque .y = wrench[4 ];
346
+ rt_publisher->msg_ .wrench .torque .z = wrench[5 ];
347
+
348
+ rt_publisher->unlockAndPublish ();
349
+ }
350
+ }
351
+
298
352
template <class HardwareInterface >
299
353
void CartesianForceController<HardwareInterface>::dynamicReconfigureCallback(Config& config,
300
354
uint32_t level)
0 commit comments