Converts between xpp-states types and xpp-messages. More...
#include <convert.h>
Static Public Member Functions | |
static xpp_msgs::StateLin3d | ToRos (const StateLin3d &xpp) |
template<typename T > | |
static T | ToRos (const Vector3d &xpp) |
static geometry_msgs::Quaternion | ToRos (const Eigen::Quaterniond xpp) |
static xpp_msgs::State6d | ToRos (const State3d &xpp) |
static xpp_msgs::RobotStateCartesian | ToRos (const RobotStateCartesian &xpp) |
static xpp_msgs::RobotStateCartesianTrajectory | ToRos (const std::vector< RobotStateCartesian > &xpp) |
static StateLin3d | ToXpp (const xpp_msgs::StateLin3d &ros) |
template<typename T > | |
static Vector3d | ToXpp (const T &ros) |
template<typename T > | |
static Endeffectors< Vector3d > | ToXpp (const std::vector< T > &ros) |
static Eigen::Quaterniond | ToXpp (const geometry_msgs::Quaternion ros) |
static State3d | ToXpp (const xpp_msgs::State6d &ros) |
static RobotStateCartesian | ToXpp (const xpp_msgs::RobotStateCartesian &ros) |
static std::vector < RobotStateCartesian > | ToXpp (const xpp_msgs::RobotStateCartesianTrajectory &ros) |
Converts between xpp-states types and xpp-messages.
ToXpp() : Convert from ROS message (xpp_msgs) to state (xpp_states). ToRos() : Convert from state (xpp_states) to ROS message (xpp_msgs).
static xpp_msgs::StateLin3d xpp::Convert::ToRos | ( | const StateLin3d & | xpp | ) | [inline, static] |
static T xpp::Convert::ToRos | ( | const Vector3d & | xpp | ) | [inline, static] |
static geometry_msgs::Quaternion xpp::Convert::ToRos | ( | const Eigen::Quaterniond | xpp | ) | [inline, static] |
static xpp_msgs::State6d xpp::Convert::ToRos | ( | const State3d & | xpp | ) | [inline, static] |
static xpp_msgs::RobotStateCartesian xpp::Convert::ToRos | ( | const RobotStateCartesian & | xpp | ) | [inline, static] |
static xpp_msgs::RobotStateCartesianTrajectory xpp::Convert::ToRos | ( | const std::vector< RobotStateCartesian > & | xpp | ) | [inline, static] |
static StateLin3d xpp::Convert::ToXpp | ( | const xpp_msgs::StateLin3d & | ros | ) | [inline, static] |
static Vector3d xpp::Convert::ToXpp | ( | const T & | ros | ) | [inline, static] |
static Endeffectors<Vector3d> xpp::Convert::ToXpp | ( | const std::vector< T > & | ros | ) | [inline, static] |
static Eigen::Quaterniond xpp::Convert::ToXpp | ( | const geometry_msgs::Quaternion | ros | ) | [inline, static] |
static State3d xpp::Convert::ToXpp | ( | const xpp_msgs::State6d & | ros | ) | [inline, static] |
static RobotStateCartesian xpp::Convert::ToXpp | ( | const xpp_msgs::RobotStateCartesian & | ros | ) | [inline, static] |
static std::vector<RobotStateCartesian> xpp::Convert::ToXpp | ( | const xpp_msgs::RobotStateCartesianTrajectory & | ros | ) | [inline, static] |