Public Member Functions | Static Public Member Functions | Private Types
moveit_controller_multidof::TransformPathConverter Class Reference

Provides methods to transform nav_msgs::Path to geometry_msgs/Transform[] and vice versa. More...

#include <PathConverter.h>

List of all members.

Public Member Functions

 TransformPathConverter ()
 ~TransformPathConverter ()

Static Public Member Functions

static void convert (const std::vector< geometry_msgs::Transform > &transforms, nav_msgs::Path &path, const std::string &frame_id, bool transforms_are_relative, const geometry_msgs::Pose &start_pose=geometry_msgs::Pose(), const ros::Time &time=ros::Time::now(), const std::vector< ros::Duration > &path_times=std::vector< ros::Duration >())
static void convert (const nav_msgs::Path &path, std::vector< geometry_msgs::Transform > &transforms, bool make_relative_transforms)
template<typename T >
static Eigen::Quaternion< TgetRotationFromTo (const Eigen::Quaternion< T > &q1, const Eigen::Quaternion< T > &q2)

Private Types

typedef Eigen::Transform
< double, 3, Eigen::Affine > 
EigenTransform

Detailed Description

Provides methods to transform nav_msgs::Path to geometry_msgs/Transform[] and vice versa.

Author:
Jennifer Buehler

Definition at line 15 of file PathConverter.h.


Member Typedef Documentation

typedef Eigen::Transform<double,3,Eigen::Affine> moveit_controller_multidof::TransformPathConverter::EigenTransform [private]

Definition at line 17 of file PathConverter.h.


Constructor & Destructor Documentation

Definition at line 19 of file PathConverter.h.


Member Function Documentation

static void moveit_controller_multidof::TransformPathConverter::convert ( const std::vector< geometry_msgs::Transform > &  transforms,
nav_msgs::Path &  path,
const std::string &  frame_id,
bool  transforms_are_relative,
const geometry_msgs::Pose &  start_pose = geometry_msgs::Pose(),
const ros::Time time = ros::Time::now(),
const std::vector< ros::Duration > &  path_times = std::vector<ros::Duration>() 
) [inline, static]
Parameters:
transforms_are_relativeif true, the transform represent relative movement. In this case, starting pose can be set with parameter start_pose.
start_poseonly relevant it transforms_are_relative, and then this is the start pose of the path
frame_idthe transforms (and start_pose) are to be expressed in this frame.
timetime of the frame_id. This is going to be set in all path points, or if path_times is set, then this applies only to the start point. Default is ros::Time::now().
path_timesif not empty, it has to be the size of transforms. It contains, for each point in transforms, the time from the start of the trajectory.

Definition at line 32 of file PathConverter.h.

static void moveit_controller_multidof::TransformPathConverter::convert ( const nav_msgs::Path &  path,
std::vector< geometry_msgs::Transform > &  transforms,
bool  make_relative_transforms 
) [inline, static]

Definition at line 99 of file PathConverter.h.

template<typename T >
static Eigen::Quaternion<T> moveit_controller_multidof::TransformPathConverter::getRotationFromTo ( const Eigen::Quaternion< T > &  q1,
const Eigen::Quaternion< T > &  q2 
) [inline, static]

Definition at line 158 of file PathConverter.h.


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


moveit_controller_multidof
Author(s): Jennifer Buehler
autogenerated on Sat Mar 2 2019 03:50:48