Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031 #include <eigen_conversions/eigen_msg.h>
00032
00033 namespace tf {
00034
00035 void pointMsgToEigen(const geometry_msgs::Point &m, Eigen::Vector3d &e)
00036 {
00037 e(0) = m.x;
00038 e(1) = m.y;
00039 e(2) = m.z;
00040 }
00041
00042 void pointEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Point &m)
00043 {
00044 m.x = e(0);
00045 m.y = e(1);
00046 m.z = e(2);
00047 }
00048
00049 void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
00050 {
00051 e = Eigen::Translation3d(m.position.x,
00052 m.position.y,
00053 m.position.z) *
00054 Eigen::Quaterniond(m.orientation.w,
00055 m.orientation.x,
00056 m.orientation.y,
00057 m.orientation.z);
00058 }
00059
00060 void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
00061 {
00062 m.position.x = e.translation()[0];
00063 m.position.y = e.translation()[1];
00064 m.position.z = e.translation()[2];
00065 Eigen::Quaterniond q = (Eigen::Quaterniond)e.linear();
00066 m.orientation.x = q.x();
00067 m.orientation.y = q.y();
00068 m.orientation.z = q.z();
00069 m.orientation.w = q.w();
00070 if (m.orientation.w < 0) {
00071 m.orientation.x *= -1;
00072 m.orientation.y *= -1;
00073 m.orientation.z *= -1;
00074 m.orientation.w *= -1;
00075 }
00076 }
00077
00078 void quaternionMsgToEigen(const geometry_msgs::Quaternion &m, Eigen::Quaterniond &e)
00079 {
00080 e = Eigen::Quaterniond(m.w, m.x, m.y, m.z);
00081 }
00082
00083 void quaternionEigenToMsg(const Eigen::Quaterniond &e, geometry_msgs::Quaternion &m)
00084 {
00085 m.x = e.x();
00086 m.y = e.y();
00087 m.z = e.z();
00088 m.w = e.w();
00089 }
00090
00091 void transformMsgToEigen(const geometry_msgs::Transform &m, Eigen::Affine3d &e)
00092 {
00093 e = Eigen::Translation3d(m.translation.x,
00094 m.translation.y,
00095 m.translation.z) *
00096 Eigen::Quaterniond(m.rotation.w,
00097 m.rotation.x,
00098 m.rotation.y,
00099 m.rotation.z);
00100 }
00101
00102 void transformEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Transform &m)
00103 {
00104 m.translation.x = e.translation()[0];
00105 m.translation.y = e.translation()[1];
00106 m.translation.z = e.translation()[2];
00107 Eigen::Quaterniond q = (Eigen::Quaterniond)e.linear();
00108 m.rotation.x = q.x();
00109 m.rotation.y = q.y();
00110 m.rotation.z = q.z();
00111 m.rotation.w = q.w();
00112 if (m.rotation.w < 0) {
00113 m.rotation.x *= -1;
00114 m.rotation.y *= -1;
00115 m.rotation.z *= -1;
00116 m.rotation.w *= -1;
00117 }
00118 }
00119
00120 void vectorMsgToEigen(const geometry_msgs::Vector3 &m, Eigen::Vector3d &e)
00121 {
00122 e(0) = m.x;
00123 e(1) = m.y;
00124 e(2) = m.z;
00125 }
00126
00127 void vectorEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Vector3 &m)
00128 {
00129 m.x = e(0);
00130 m.y = e(1);
00131 m.z = e(2);
00132 }
00133
00134 void twistMsgToEigen(const geometry_msgs::Twist &m, Eigen::Matrix<double,6,1> &e)
00135 {
00136 e[0] = m.linear.x;
00137 e[1] = m.linear.y;
00138 e[2] = m.linear.z;
00139 e[3] = m.angular.x;
00140 e[4] = m.angular.y;
00141 e[5] = m.angular.z;
00142 }
00143
00144 void twistEigenToMsg(const Eigen::Matrix<double,6,1> &e, geometry_msgs::Twist &m)
00145 {
00146 m.linear.x = e[0];
00147 m.linear.y = e[1];
00148 m.linear.z = e[2];
00149 m.angular.x = e[3];
00150 m.angular.y = e[4];
00151 m.angular.z = e[5];
00152 }
00153
00154 void wrenchMsgToEigen(const geometry_msgs::Wrench &m, Eigen::Matrix<double,6,1> &e)
00155 {
00156 e[0] = m.force.x;
00157 e[1] = m.force.y;
00158 e[2] = m.force.z;
00159 e[3] = m.torque.x;
00160 e[4] = m.torque.y;
00161 e[5] = m.torque.z;
00162 }
00163
00164 void wrenchEigenToMsg(const Eigen::Matrix<double,6,1> &e, geometry_msgs::Wrench &m)
00165 {
00166 m.force.x = e[0];
00167 m.force.y = e[1];
00168 m.force.z = e[2];
00169 m.torque.x = e[3];
00170 m.torque.y = e[4];
00171 m.torque.z = e[5];
00172 }
00173
00174 }