34 #include <xpp_msgs/RobotStateJoint.h>
40 const std::string& cart_topic,
41 const std::string& joint_topic)
59 Eigen::Matrix3d B_R_W = cart.base_.ang.q.normalized().toRotationMatrix().inverse();
61 for (
auto ee : ee_B.GetEEsOrdered())
62 ee_B.at(ee) = B_R_W * (cart.ee_motion_.at(ee).p_ - cart.base_.lin.p_);
66 xpp_msgs::RobotStateJoint joint_msg;
67 joint_msg.base = cart_msg.base;
68 joint_msg.ee_contact = cart_msg.ee_contact;
69 joint_msg.time_from_start = cart_msg.time_from_start;
70 joint_msg.joint_state.position = std::vector<double>(q.data(), q.data()+q.size());