Skip to content

Commit acc191d

Browse files
committed
Publish wrench state feedback
1 parent 82883cb commit acc191d

File tree

2 files changed

+77
-2
lines changed

2 files changed

+77
-2
lines changed

cartesian_force_controller/include/cartesian_force_controller/cartesian_force_controller.h

+21
Original file line numberDiff line numberDiff line change
@@ -103,6 +103,18 @@ class CartesianForceController : public virtual cartesian_controller_base::Carte
103103
std::string m_new_ft_sensor_ref;
104104
void setFtSensorReferenceFrame(const std::string& new_ref);
105105

106+
/**
107+
* @brief Publish the controller's state wrench
108+
*
109+
* The data are w.r.t. the specified robot base link.
110+
* If this function is called after `computeJointControlCmds()` has
111+
* been called, then the controller's internal state represents the state
112+
* right after the error computation, and corresponds to the new target
113+
* state that will be send to the actuators in this control cycle.
114+
*/
115+
void publishStateWrenchFeedback(realtime_tools::RealtimePublisherSharedPtr<geometry_msgs::WrenchStamped>& rt_publisher,
116+
ctrl::Vector6D& wrench);
117+
106118
private:
107119
ctrl::Vector6D compensateGravity();
108120

@@ -136,6 +148,15 @@ class CartesianForceController : public virtual cartesian_controller_base::Carte
136148

137149
std::shared_ptr<dynamic_reconfigure::Server<Config> > m_dyn_conf_server;
138150
dynamic_reconfigure::Server<Config>::CallbackType m_callback_type;
151+
152+
realtime_tools::RealtimePublisherSharedPtr<geometry_msgs::WrenchStamped>
153+
m_feedback_gravity_wrench_publisher;
154+
realtime_tools::RealtimePublisherSharedPtr<geometry_msgs::WrenchStamped>
155+
m_feedback_sensor_wrench_publisher;
156+
realtime_tools::RealtimePublisherSharedPtr<geometry_msgs::WrenchStamped>
157+
m_feedback_target_wrench_publisher;
158+
realtime_tools::RealtimePublisherSharedPtr<geometry_msgs::WrenchStamped>
159+
m_feedback_net_force_wrench_publisher;
139160
};
140161

141162
}

cartesian_force_controller/include/cartesian_force_controller/cartesian_force_controller.hpp

+56-2
Original file line numberDiff line numberDiff line change
@@ -113,6 +113,23 @@ init(HardwareInterface* hw, ros::NodeHandle& nh)
113113
m_target_wrench.setZero();
114114
m_ft_sensor_wrench.setZero();
115115

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+
116133
// Connect dynamic reconfigure and overwrite the default values with values
117134
// on the parameter server. This is done automatically if parameters with
118135
// the according names exist.
@@ -185,10 +202,28 @@ computeForceError()
185202
target_wrench = m_target_wrench;
186203
}
187204

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+
188211
// 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
190214
+ 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;
192227
}
193228

194229
template <class HardwareInterface>
@@ -295,6 +330,25 @@ signalTaringCallback(std_srvs::Trigger::Request& req, std_srvs::Trigger::Respons
295330
return true;
296331
}
297332

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+
298352
template <class HardwareInterface>
299353
void CartesianForceController<HardwareInterface>::dynamicReconfigureCallback(Config& config,
300354
uint32_t level)

0 commit comments

Comments
 (0)