Provides methods to transform nav_msgs::Path to geometry_msgs/Transform[] and vice versa. More...
#include <PathConverter.h>
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< T > | getRotationFromTo (const Eigen::Quaternion< T > &q1, const Eigen::Quaternion< T > &q2) |
Private Types | |
typedef Eigen::Transform < double, 3, Eigen::Affine > | EigenTransform |
Provides methods to transform nav_msgs::Path to geometry_msgs/Transform[] and vice versa.
Definition at line 15 of file PathConverter.h.
typedef Eigen::Transform<double,3,Eigen::Affine> moveit_controller_multidof::TransformPathConverter::EigenTransform [private] |
Definition at line 17 of file PathConverter.h.
Definition at line 19 of file PathConverter.h.
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] |
transforms_are_relative | if true, the transform represent relative movement. In this case, starting pose can be set with parameter start_pose. |
start_pose | only relevant it transforms_are_relative, and then this is the start pose of the path |
frame_id | the transforms (and start_pose) are to be expressed in this frame. |
time | time 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_times | if 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.
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.