30 #ifndef XPP_ROS_CONVERSIONS_H_
31 #define XPP_ROS_CONVERSIONS_H_
35 #include <xpp_msgs/StateLin3d.h>
36 #include <xpp_msgs/State6d.h>
37 #include <xpp_msgs/RobotStateCartesian.h>
38 #include <xpp_msgs/RobotStateCartesianTrajectory.h>
54 ToXpp(
const xpp_msgs::StateLin3d& ros)
57 point.
p_.x() = ros.pos.x;
58 point.p_.y() = ros.pos.y;
59 point.p_.z() = ros.pos.z;
61 point.v_.x() = ros.vel.x;
62 point.v_.y() = ros.vel.y;
63 point.v_.z() = ros.vel.z;
65 point.a_.x() = ros.acc.x;
66 point.a_.y() = ros.acc.y;
67 point.a_.z() = ros.acc.z;
72 static xpp_msgs::StateLin3d
75 xpp_msgs::StateLin3d ros;
76 ros.pos.x =
xpp.p_.x();
77 ros.pos.y =
xpp.p_.y();
78 ros.pos.z =
xpp.p_.z();
80 ros.vel.x =
xpp.v_.x();
81 ros.vel.y =
xpp.v_.y();
82 ros.vel.z =
xpp.v_.z();
84 ros.acc.x =
xpp.a_.x();
85 ros.acc.y =
xpp.a_.y();
86 ros.acc.z =
xpp.a_.z();
96 vec << ros.x, ros.y, ros.z;
114 ToXpp(
const std::vector<T>& ros)
118 for (
auto ee :
xpp.GetEEsOrdered())
125 ToXpp(
const geometry_msgs::Quaternion ros)
136 static geometry_msgs::Quaternion
139 geometry_msgs::Quaternion ros;
148 static xpp_msgs::State6d
151 xpp_msgs::State6d msg;
153 msg.pose.position = ToRos<geometry_msgs::Point>(
xpp.lin.p_);
154 msg.twist.linear = ToRos<geometry_msgs::Vector3>(
xpp.lin.v_);
155 msg.accel.linear = ToRos<geometry_msgs::Vector3>(
xpp.lin.a_);
157 msg.pose.orientation =
ToRos(
xpp.ang.q);
158 msg.twist.angular = ToRos<geometry_msgs::Vector3>(
xpp.ang.w);
159 msg.accel.angular = ToRos<geometry_msgs::Vector3>(
xpp.ang.wd);
165 ToXpp(
const xpp_msgs::State6d& ros)
169 xpp.lin.p_ =
ToXpp(ros.pose.position);
170 xpp.lin.v_ =
ToXpp(ros.twist.linear);
171 xpp.lin.a_ =
ToXpp(ros.accel.linear);
173 xpp.ang.q =
ToXpp(ros.pose.orientation);
174 xpp.ang.w =
ToXpp(ros.twist.angular);
175 xpp.ang.wd =
ToXpp(ros.accel.angular);
180 static xpp_msgs::RobotStateCartesian
183 xpp_msgs::RobotStateCartesian ros;
186 ros.time_from_start = ros::Duration(
xpp.t_global_);
188 for (
auto ee :
xpp.ee_contact_.GetEEsOrdered()) {
189 ros.ee_motion. push_back(
ToRos(
xpp.ee_motion_.at(ee)));
190 ros.ee_contact.push_back(
xpp.ee_contact_.at(ee));
191 ros.ee_forces. push_back(ToRos<geometry_msgs::Vector3>(
xpp.ee_forces_.at(ee)));
197 static RobotStateCartesian
198 ToXpp(
const xpp_msgs::RobotStateCartesian& ros)
201 int n_ee = ros.ee_motion.size();
202 RobotStateCartesian
xpp(n_ee);
205 xpp.t_global_ = ros.time_from_start.toSec();
207 for (
auto ee :
xpp.ee_contact_.GetEEsOrdered()) {
208 xpp.ee_motion_.at(ee) =
ToXpp(ros.ee_motion.at(ee));
209 xpp.ee_contact_.at(ee) = ros.ee_contact.at(ee);
210 xpp.ee_forces_.at(ee) =
ToXpp(ros.ee_forces.at(ee));
216 static xpp_msgs::RobotStateCartesianTrajectory
217 ToRos(
const std::vector<RobotStateCartesian>&
xpp)
219 xpp_msgs::RobotStateCartesianTrajectory msg;
221 for (
const auto state :
xpp) {
222 auto state_msg =
ToRos(state);
223 msg.points.push_back(state_msg);
229 static std::vector<RobotStateCartesian>
230 ToXpp(
const xpp_msgs::RobotStateCartesianTrajectory& ros)
232 std::vector<RobotStateCartesian> xpp_vec;
234 for (
const auto ros_state : ros.points) {
236 xpp_vec.push_back(
xpp);