Public Member Functions | Private Member Functions | Private Attributes | List of all members
xpp::CartesianJointConverter Class Reference

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_
 

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 78 of file cartesian_joint_converter.h.

Constructor & Destructor Documentation

◆ CartesianJointConverter()

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 66 of file cartesian_joint_converter.cc.

◆ ~CartesianJointConverter()

virtual xpp::CartesianJointConverter::~CartesianJointConverter ( )
virtualdefault

Member Function Documentation

◆ StateCallback()

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

Definition at line 81 of file cartesian_joint_converter.cc.

Member Data Documentation

◆ cart_state_sub_

ros::Subscriber xpp::CartesianJointConverter::cart_state_sub_
private

Definition at line 121 of file cartesian_joint_converter.h.

◆ inverse_kinematics_

InverseKinematics::Ptr xpp::CartesianJointConverter::inverse_kinematics_
private

Definition at line 124 of file cartesian_joint_converter.h.

◆ joint_state_pub_

ros::Publisher xpp::CartesianJointConverter::joint_state_pub_
private

Definition at line 122 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 Wed Mar 2 2022 01:14:16