convert.h
Go to the documentation of this file.
00001 /******************************************************************************
00002 Copyright (c) 2017, Alexander W. Winkler. All rights reserved.
00003 
00004 Redistribution and use in source and binary forms, with or without
00005 modification, are permitted provided that the following conditions are met:
00006 
00007 * Redistributions of source code must retain the above copyright notice, this
00008   list of conditions and the following disclaimer.
00009 
00010 * Redistributions in binary form must reproduce the above copyright notice,
00011   this list of conditions and the following disclaimer in the documentation
00012   and/or other materials provided with the distribution.
00013 
00014 * Neither the name of the copyright holder nor the names of its
00015   contributors may be used to endorse or promote products derived from
00016   this software without specific prior written permission.
00017 
00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00021 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
00022 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00023 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00024 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00025 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00026 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00027 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028 ******************************************************************************/
00029 
00030 #ifndef XPP_ROS_CONVERSIONS_H_
00031 #define XPP_ROS_CONVERSIONS_H_
00032 
00033 #include <vector>
00034 
00035 #include <xpp_msgs/StateLin3d.h>
00036 #include <xpp_msgs/State6d.h>
00037 #include <xpp_msgs/RobotStateCartesian.h>
00038 #include <xpp_msgs/RobotStateCartesianTrajectory.h>
00039 
00040 #include <xpp_states/state.h>
00041 #include <xpp_states/robot_state_cartesian.h>
00042 
00043 namespace xpp {
00044 
00051 struct Convert {
00052 
00053 static StateLin3d
00054 ToXpp(const xpp_msgs::StateLin3d& ros)
00055 {
00056   StateLin3d point;
00057   point.p_.x() = ros.pos.x;
00058   point.p_.y() = ros.pos.y;
00059   point.p_.z() = ros.pos.z;
00060 
00061   point.v_.x() = ros.vel.x;
00062   point.v_.y() = ros.vel.y;
00063   point.v_.z() = ros.vel.z;
00064 
00065   point.a_.x() = ros.acc.x;
00066   point.a_.y() = ros.acc.y;
00067   point.a_.z() = ros.acc.z;
00068 
00069   return point;
00070 }
00071 
00072 static xpp_msgs::StateLin3d
00073 ToRos(const StateLin3d& xpp)
00074 {
00075   xpp_msgs::StateLin3d ros;
00076   ros.pos.x = xpp.p_.x();
00077   ros.pos.y = xpp.p_.y();
00078   ros.pos.z = xpp.p_.z();
00079 
00080   ros.vel.x = xpp.v_.x();
00081   ros.vel.y = xpp.v_.y();
00082   ros.vel.z = xpp.v_.z();
00083 
00084   ros.acc.x = xpp.a_.x();
00085   ros.acc.y = xpp.a_.y();
00086   ros.acc.z = xpp.a_.z();
00087 
00088   return ros;
00089 }
00090 
00091 template<typename T>
00092 static Vector3d
00093 ToXpp(const T& ros)
00094 {
00095   Vector3d vec;
00096   vec << ros.x, ros.y, ros.z;
00097   return vec;
00098 }
00099 
00100 template<typename T>
00101 static T
00102 ToRos(const Vector3d& xpp)
00103 {
00104   T ros;
00105   ros.x = xpp.x();
00106   ros.y = xpp.y();
00107   ros.z = xpp.z();
00108 
00109   return ros;
00110 }
00111 
00112 template<typename T>
00113 static Endeffectors<Vector3d>
00114 ToXpp(const std::vector<T>& ros)
00115 {
00116   Endeffectors<Vector3d> xpp(ros.size());
00117 
00118   for (auto ee : xpp.GetEEsOrdered())
00119     xpp.at(ee) = ToXpp(ros.at(ee));
00120 
00121   return xpp;
00122 }
00123 
00124 static Eigen::Quaterniond
00125 ToXpp(const geometry_msgs::Quaternion ros)
00126 {
00127   Eigen::Quaterniond xpp;
00128   xpp.w() = ros.w;
00129   xpp.x() = ros.x;
00130   xpp.y() = ros.y;
00131   xpp.z() = ros.z;
00132 
00133   return xpp;
00134 }
00135 
00136 static geometry_msgs::Quaternion
00137 ToRos(const Eigen::Quaterniond xpp)
00138 {
00139   geometry_msgs::Quaternion ros;
00140   ros.w = xpp.w();
00141   ros.x = xpp.x();
00142   ros.y = xpp.y();
00143   ros.z = xpp.z();
00144 
00145   return ros;
00146 }
00147 
00148 static xpp_msgs::State6d
00149 ToRos(const State3d& xpp)
00150 {
00151   xpp_msgs::State6d msg;
00152 
00153   msg.pose.position = ToRos<geometry_msgs::Point>(xpp.lin.p_);
00154   msg.twist.linear  = ToRos<geometry_msgs::Vector3>(xpp.lin.v_);
00155   msg.accel.linear  = ToRos<geometry_msgs::Vector3>(xpp.lin.a_);
00156 
00157   msg.pose.orientation = ToRos(xpp.ang.q);
00158   msg.twist.angular    = ToRos<geometry_msgs::Vector3>(xpp.ang.w);
00159   msg.accel.angular    = ToRos<geometry_msgs::Vector3>(xpp.ang.wd);
00160 
00161   return msg;
00162 }
00163 
00164 static State3d
00165 ToXpp(const xpp_msgs::State6d& ros)
00166 {
00167   State3d xpp;
00168 
00169   xpp.lin.p_ = ToXpp(ros.pose.position);
00170   xpp.lin.v_ = ToXpp(ros.twist.linear);
00171   xpp.lin.a_ = ToXpp(ros.accel.linear);
00172 
00173   xpp.ang.q = ToXpp(ros.pose.orientation);
00174   xpp.ang.w = ToXpp(ros.twist.angular);
00175   xpp.ang.wd = ToXpp(ros.accel.angular);
00176 
00177   return xpp;
00178 }
00179 
00180 static xpp_msgs::RobotStateCartesian
00181 ToRos(const RobotStateCartesian& xpp)
00182 {
00183   xpp_msgs::RobotStateCartesian ros;
00184 
00185   ros.base            = ToRos(xpp.base_);
00186   ros.time_from_start = ros::Duration(xpp.t_global_);
00187 
00188   for (auto ee : xpp.ee_contact_.GetEEsOrdered()) {
00189     ros.ee_motion. push_back(ToRos(xpp.ee_motion_.at(ee)));
00190     ros.ee_contact.push_back(xpp.ee_contact_.at(ee));
00191     ros.ee_forces. push_back(ToRos<geometry_msgs::Vector3>(xpp.ee_forces_.at(ee)));
00192   }
00193 
00194   return ros;
00195 }
00196 
00197 static RobotStateCartesian
00198 ToXpp(const xpp_msgs::RobotStateCartesian& ros)
00199 {
00200 
00201   int n_ee = ros.ee_motion.size();
00202   RobotStateCartesian xpp(n_ee);
00203 
00204   xpp.base_     = ToXpp(ros.base);
00205   xpp.t_global_ = ros.time_from_start.toSec();
00206 
00207   for (auto ee : xpp.ee_contact_.GetEEsOrdered()) {
00208     xpp.ee_motion_.at(ee)  = ToXpp(ros.ee_motion.at(ee));
00209     xpp.ee_contact_.at(ee) = ros.ee_contact.at(ee);
00210     xpp.ee_forces_.at(ee)  = ToXpp(ros.ee_forces.at(ee));
00211   }
00212 
00213   return xpp;
00214 }
00215 
00216 static xpp_msgs::RobotStateCartesianTrajectory
00217 ToRos(const std::vector<RobotStateCartesian>& xpp)
00218 {
00219   xpp_msgs::RobotStateCartesianTrajectory msg;
00220 
00221   for (const auto state : xpp) {
00222     auto state_msg = ToRos(state);
00223     msg.points.push_back(state_msg);
00224   }
00225 
00226   return msg;
00227 }
00228 
00229 static std::vector<RobotStateCartesian>
00230 ToXpp(const xpp_msgs::RobotStateCartesianTrajectory& ros)
00231 {
00232   std::vector<RobotStateCartesian> xpp_vec;
00233 
00234   for (const auto ros_state : ros.points) {
00235     auto xpp = ToXpp(ros_state);
00236     xpp_vec.push_back(xpp);
00237   }
00238 
00239   return xpp_vec;
00240 }
00241 
00242 };
00243 
00244 } // namespace xpp
00245 
00246 #endif /* XPP_ROS_CONVERSIONS_H_ */


xpp_states
Author(s): Alexander W. Winkler
autogenerated on Fri Apr 5 2019 02:55:50