34 #include <xpp_msgs/RobotStateJoint.h> 40 const std::string& cart_topic,
41 const std::string& joint_topic)
50 ROS_DEBUG(
"Publishing to: %s", joint_state_pub_.getTopic().c_str());
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());
std::string getTopic() const
std::shared_ptr< InverseKinematics > Ptr
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
InverseKinematics::Ptr inverse_kinematics_
ros::Publisher joint_state_pub_
void publish(const boost::shared_ptr< M > &message) const
ros::Subscriber cart_state_sub_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void StateCallback(const xpp_msgs::RobotStateCartesian &msg)
CartesianJointConverter(const InverseKinematics::Ptr &ik, const std::string &cart_topic, const std::string &joint_topic)
Creates a converter initializing the subscriber and publisher.
static StateLin3d ToXpp(const xpp_msgs::StateLin3d &ros)