30 #ifndef XPP_VIS_CARTESIAN_JOINT_CONVERTER_H_ 31 #define XPP_VIS_CARTESIAN_JOINT_CONVERTER_H_ 38 #include <xpp_msgs/RobotStateCartesian.h> 60 const std::string& cart_topic,
61 const std::string& joint_topic);
std::shared_ptr< InverseKinematics > Ptr
InverseKinematics::Ptr inverse_kinematics_
ros::Publisher joint_state_pub_
ros::Subscriber cart_state_sub_
virtual ~CartesianJointConverter()=default
Converts a Cartesian robot representation to joint angles.
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.