Public Member Functions | Private Member Functions | Private Attributes
xpp::CartesianJointConverter Class Reference

Converts a Cartesian robot representation to joint angles. More...

#include <cartesian_joint_converter.h>

List of all members.

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.
virtual ~CartesianJointConverter ()

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_

Detailed Description

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.


Constructor & Destructor Documentation

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.

Parameters:
ikThe InverseKinematics to use for conversion.
cart_topicThe ROS topic containing the Cartesian robot state.
joint_topicThe ROS topic to publish for the URDF visualization.

Definition at line 39 of file cartesian_joint_converter.cc.


Member Function Documentation

void xpp::CartesianJointConverter::StateCallback ( const xpp_msgs::RobotStateCartesian &  msg) [private]

Definition at line 54 of file cartesian_joint_converter.cc.


Member Data Documentation

Definition at line 67 of file cartesian_joint_converter.h.

InverseKinematics::Ptr xpp::CartesianJointConverter::inverse_kinematics_ [private]

Definition at line 70 of file cartesian_joint_converter.h.

Definition at line 68 of file cartesian_joint_converter.h.


The documentation for this class was generated from the following files:


xpp_vis
Author(s): Alexander W. Winkler
autogenerated on Fri Apr 5 2019 02:55:52