diff --git a/cartesian_force_controller/include/cartesian_force_controller/cartesian_force_controller.h b/cartesian_force_controller/include/cartesian_force_controller/cartesian_force_controller.h index 0cf07481..a8b59dd0 100644 --- a/cartesian_force_controller/include/cartesian_force_controller/cartesian_force_controller.h +++ b/cartesian_force_controller/include/cartesian_force_controller/cartesian_force_controller.h @@ -103,6 +103,14 @@ class CartesianForceController : public virtual cartesian_controller_base::Carte std::string m_new_ft_sensor_ref; void setFtSensorReferenceFrame(const std::string& new_ref); + /** + * @brief Publish the controller's wrenches (sensor, gravity, target and net force) + * + * The data are w.r.t. the specified robot base link. + */ + void publishStateWrenchFeedback(realtime_tools::RealtimePublisherSharedPtr& rt_publisher, + ctrl::Vector6D& wrench); + private: ctrl::Vector6D compensateGravity(); @@ -136,6 +144,15 @@ class CartesianForceController : public virtual cartesian_controller_base::Carte std::shared_ptr > m_dyn_conf_server; dynamic_reconfigure::Server::CallbackType m_callback_type; + + realtime_tools::RealtimePublisherSharedPtr + m_feedback_gravity_wrench_publisher; + realtime_tools::RealtimePublisherSharedPtr + m_feedback_sensor_wrench_publisher; + realtime_tools::RealtimePublisherSharedPtr + m_feedback_target_wrench_publisher; + realtime_tools::RealtimePublisherSharedPtr + m_feedback_net_force_wrench_publisher; }; } diff --git a/cartesian_force_controller/include/cartesian_force_controller/cartesian_force_controller.hpp b/cartesian_force_controller/include/cartesian_force_controller/cartesian_force_controller.hpp index 107d6499..95ebf7ea 100644 --- a/cartesian_force_controller/include/cartesian_force_controller/cartesian_force_controller.hpp +++ b/cartesian_force_controller/include/cartesian_force_controller/cartesian_force_controller.hpp @@ -113,6 +113,23 @@ init(HardwareInterface* hw, ros::NodeHandle& nh) m_target_wrench.setZero(); m_ft_sensor_wrench.setZero(); + // Controller-internal state publishing + m_feedback_gravity_wrench_publisher = + std::make_shared >( + nh, "current_gravity_wrench", 3); + + m_feedback_sensor_wrench_publisher = + std::make_shared >( + nh, "current_sensor_wrench", 3); + + m_feedback_target_wrench_publisher = + std::make_shared >( + nh, "current_target_wrench", 3); + + m_feedback_net_force_wrench_publisher = + std::make_shared >( + nh, "current_net_force_wrench", 3); + // Connect dynamic reconfigure and overwrite the default values with values // on the parameter server. This is done automatically if parameters with // the according names exist. @@ -185,10 +202,28 @@ computeForceError() target_wrench = m_target_wrench; } + ctrl::Vector6D sensor_wrench; + sensor_wrench = Base::displayInBaseLink(m_ft_sensor_wrench,m_new_ft_sensor_ref); + + ctrl::Vector6D gravity_wrench; + gravity_wrench = compensateGravity(); + // Superimpose target wrench and sensor wrench in base frame - return Base::displayInBaseLink(m_ft_sensor_wrench,m_new_ft_sensor_ref) + ctrl::Vector6D net_force_wrench; + net_force_wrench = sensor_wrench + target_wrench - + compensateGravity(); + + gravity_wrench; + + // Publish wrench state feedback + if (Base::m_publish_state_feedback) + { + publishStateWrenchFeedback(m_feedback_sensor_wrench_publisher, sensor_wrench); + publishStateWrenchFeedback(m_feedback_target_wrench_publisher, target_wrench); + publishStateWrenchFeedback(m_feedback_gravity_wrench_publisher, gravity_wrench); + publishStateWrenchFeedback(m_feedback_net_force_wrench_publisher, net_force_wrench); + } + + return net_force_wrench; } template @@ -295,6 +330,25 @@ signalTaringCallback(std_srvs::Trigger::Request& req, std_srvs::Trigger::Respons return true; } +template +void CartesianForceController:: +publishStateWrenchFeedback(realtime_tools::RealtimePublisherSharedPtr& rt_publisher, + ctrl::Vector6D& wrench) +{ + if (rt_publisher->trylock()){ + rt_publisher->msg_.header.stamp = ros::Time::now(); + rt_publisher->msg_.header.frame_id = Base::m_robot_base_link; + rt_publisher->msg_.wrench.force.x = wrench[0]; + rt_publisher->msg_.wrench.force.y = wrench[1]; + rt_publisher->msg_.wrench.force.z = wrench[2]; + rt_publisher->msg_.wrench.torque.x = wrench[3]; + rt_publisher->msg_.wrench.torque.y = wrench[4]; + rt_publisher->msg_.wrench.torque.z = wrench[5]; + + rt_publisher->unlockAndPublish(); + } +} + template void CartesianForceController::dynamicReconfigureCallback(Config& config, uint32_t level)