Converts a Cartesian robot representation to joint angles. More...
#include <cartesian_joint_converter.h>
Public Member Functions | |
CartesianJointConverter (const InverseKinematics::Ptr &ik, const std::string &cart_topic, const std::string &joint_topic) | |
Creates a converter initializing the subscriber and publisher. More... | |
virtual | ~CartesianJointConverter ()=default |
Private Member Functions | |
void | StateCallback (const xpp_msgs::RobotStateCartesian &msg) |
Private Attributes | |
ros::Subscriber | cart_state_sub_ |
InverseKinematics::Ptr | inverse_kinematics_ |
ros::Publisher | joint_state_pub_ |
Converts a Cartesian robot representation to joint angles.
This class subscribes to a Cartesian robot state message and publishes the, through inverse kinematics converted, joint state message. This can then be used to visualize URDFs in RVIZ.
Definition at line 51 of file cartesian_joint_converter.h.
xpp::CartesianJointConverter::CartesianJointConverter | ( | const InverseKinematics::Ptr & | ik, |
const std::string & | cart_topic, | ||
const std::string & | joint_topic | ||
) |
Creates a converter initializing the subscriber and publisher.
ik | The InverseKinematics to use for conversion. |
cart_topic | The ROS topic containing the Cartesian robot state. |
joint_topic | The ROS topic to publish for the URDF visualization. |
Definition at line 39 of file cartesian_joint_converter.cc.
|
virtualdefault |
|
private |
Definition at line 54 of file cartesian_joint_converter.cc.
|
private |
Definition at line 67 of file cartesian_joint_converter.h.
|
private |
Definition at line 70 of file cartesian_joint_converter.h.
|
private |
Definition at line 68 of file cartesian_joint_converter.h.