00001 #include <generic_control_toolbox/wrench_manager.hpp>
00002
00003 namespace generic_control_toolbox
00004 {
00005 WrenchManager::WrenchManager(ros::NodeHandle nh) : nh_(nh)
00006 {
00007 if (!nh_.getParam("wrench_manager/max_tf_attempts", max_tf_attempts_))
00008 {
00009 ROS_WARN(
00010 "WrenchManager: Missing max_tf_attempts parameter, setting default");
00011 max_tf_attempts_ = 5;
00012 }
00013 }
00014
00015 WrenchManager::~WrenchManager() {}
00016
00017 bool WrenchManager::initializeWrenchComm(
00018 const std::string &end_effector, const std::string &sensor_frame,
00019 const std::string &gripping_point_frame, const std::string &sensor_topic,
00020 const std::string &calib_matrix_param)
00021 {
00022 if (sensor_frame_.find(end_effector) != sensor_frame_.end())
00023 {
00024 ROS_ERROR(
00025 "Cannot initialize wrench subscriber for end-effector %s: already "
00026 "initialized",
00027 end_effector.c_str());
00028 return false;
00029 }
00030
00031
00032 geometry_msgs::PoseStamped sensor_to_gripping_point;
00033 sensor_to_gripping_point.header.frame_id = sensor_frame;
00034 sensor_to_gripping_point.header.stamp = ros::Time(0);
00035 sensor_to_gripping_point.pose.position.x = 0;
00036 sensor_to_gripping_point.pose.position.y = 0;
00037 sensor_to_gripping_point.pose.position.z = 0;
00038 sensor_to_gripping_point.pose.orientation.x = 0;
00039 sensor_to_gripping_point.pose.orientation.y = 0;
00040 sensor_to_gripping_point.pose.orientation.z = 0;
00041 sensor_to_gripping_point.pose.orientation.w = 1;
00042
00043 int attempts;
00044 for (attempts = 0; attempts < max_tf_attempts_; attempts++)
00045 {
00046 try
00047 {
00048 listener_.transformPose(gripping_point_frame, sensor_to_gripping_point,
00049 sensor_to_gripping_point);
00050 break;
00051 }
00052 catch (tf::TransformException ex)
00053 {
00054 ROS_WARN("TF exception in wrench manager: %s", ex.what());
00055 }
00056 ros::Duration(0.1).sleep();
00057 }
00058
00059 if (attempts >= max_tf_attempts_)
00060 {
00061 ROS_ERROR(
00062 "WrenchManager: could not find the transform between the sensor frame "
00063 "%s and gripping point %s",
00064 sensor_frame.c_str(), gripping_point_frame.c_str());
00065 return false;
00066 }
00067
00068 Eigen::MatrixXd C;
00069 if (!parser_.parseMatrixData(C, calib_matrix_param, nh_))
00070 {
00071 ROS_ERROR(
00072 "WrenchManager: missing force torque sensor calibration matrix "
00073 "parameter %s",
00074 calib_matrix_param.c_str());
00075 return false;
00076 }
00077
00078 if (C.cols() != 6 || C.rows() != 6)
00079 {
00080 ROS_ERROR("WrenchManager: calibration matrix must be 6x6. Got %ldx%ld",
00081 C.rows(), C.cols());
00082 return false;
00083 }
00084
00085
00086 KDL::Frame sensor_to_gripping_point_kdl;
00087 calibration_matrix_[end_effector] = C;
00088 tf::poseMsgToKDL(sensor_to_gripping_point.pose, sensor_to_gripping_point_kdl);
00089 sensor_frame_[end_effector] = sensor_frame;
00090 sensor_to_gripping_point_[end_effector] = sensor_to_gripping_point_kdl;
00091 measured_wrench_[end_effector] = KDL::Wrench::Zero();
00092 ft_sub_[end_effector] =
00093 nh_.subscribe(sensor_topic, 1, &WrenchManager::forceTorqueCB, this);
00094 gripping_frame_[end_effector] = gripping_point_frame;
00095 processed_ft_pub_[end_effector] = nh_.advertise<geometry_msgs::WrenchStamped>(
00096 sensor_topic + "_converted", 1);
00097
00098 return true;
00099 }
00100
00101 bool WrenchManager::wrenchAtGrippingPoint(
00102 const std::string &end_effector, Eigen::Matrix<double, 6, 1> &wrench) const
00103 {
00104 if (sensor_frame_.find(end_effector) == sensor_frame_.end())
00105 {
00106 return false;
00107 }
00108
00109 KDL::Wrench wrench_kdl;
00110 geometry_msgs::WrenchStamped temp_wrench;
00111 wrench_kdl = sensor_to_gripping_point_.at(end_effector) *
00112 measured_wrench_.at(end_effector);
00113 tf::wrenchKDLToEigen(wrench_kdl, wrench);
00114
00115
00116 tf::wrenchKDLToMsg(wrench_kdl, temp_wrench.wrench);
00117 temp_wrench.header.frame_id = gripping_frame_.at(end_effector);
00118 temp_wrench.header.stamp = ros::Time::now();
00119 processed_ft_pub_.at(end_effector).publish(temp_wrench);
00120
00121 return true;
00122 }
00123
00124 bool WrenchManager::wrenchAtSensorPoint(
00125 const std::string &end_effector, Eigen::Matrix<double, 6, 1> &wrench) const
00126 {
00127 if (sensor_frame_.find(end_effector) == sensor_frame_.end())
00128 {
00129 return false;
00130 }
00131
00132 tf::wrenchKDLToEigen(measured_wrench_.at(end_effector), wrench);
00133
00134 return true;
00135 }
00136
00137 void WrenchManager::forceTorqueCB(
00138 const geometry_msgs::WrenchStamped::ConstPtr &msg)
00139 {
00140 std::string eef;
00141 for (auto const &it : sensor_frame_)
00142 {
00143 if (msg->header.frame_id == it.second)
00144 {
00145 eef = it.first;
00146 break;
00147 }
00148 }
00149
00150 if (eef.empty())
00151 {
00152 ROS_ERROR(
00153 "WrenchManager: got wrench message from sensor at frame %s, which was "
00154 "not configured in the wrench manager",
00155 msg->header.frame_id.c_str());
00156 return;
00157 }
00158
00159
00160 Eigen::Matrix<double, 6, 1> wrench_eig;
00161 tf::wrenchMsgToEigen(msg->wrench, wrench_eig);
00162 wrench_eig = calibration_matrix_.at(eef) * wrench_eig;
00163 tf::wrenchEigenToKDL(wrench_eig, measured_wrench_.at(eef));
00164 }
00165
00166 bool setWrenchManager(const ArmInfo &arm_info, WrenchManager &manager)
00167 {
00168 if (arm_info.has_ft_sensor)
00169 {
00170 if (!manager.initializeWrenchComm(
00171 arm_info.kdl_eef_frame, arm_info.sensor_frame,
00172 arm_info.gripping_frame, arm_info.sensor_topic,
00173 arm_info.name + "/sensor_calib"))
00174 {
00175 return false;
00176 }
00177
00178 ROS_DEBUG("WrenchManager: successfully initialized wrench comms for arm %s",
00179 arm_info.name.c_str());
00180 }
00181 else
00182 {
00183 ROS_WARN("WrenchManager: end-effector %s has no F/T sensor.",
00184 arm_info.kdl_eef_frame.c_str());
00185 }
00186
00187 return true;
00188 }
00189
00190 bool setWrenchManager(const ArmInfo &arm_info,
00191 std::shared_ptr<WrenchManager> &manager)
00192 {
00193 return setWrenchManager(arm_info, *manager);
00194 }
00195 }