Public Types | Public Member Functions | Protected Attributes
vigir_footstep_planning::FootPoseTransformer Class Reference

#include <foot_pose_transformer.h>

List of all members.

Public Types

typedef boost::shared_ptr
< const FootPoseTransformer
ConstPtr
typedef boost::shared_ptr
< FootPoseTransformer
Ptr

Public Member Functions

 FootPoseTransformer (ros::NodeHandle &nh)
msgs::ErrorStatus transform (geometry_msgs::Pose &pose, const tf::Transform &transform) const
msgs::ErrorStatus transform (msgs::Foot &foot, const std::string &target_frame) const
msgs::ErrorStatus transform (msgs::Feet &feet, const std::string &target_frame) const
msgs::ErrorStatus transform (msgs::Step &step, const std::string &target_frame) const
msgs::ErrorStatus transform (msgs::StepPlan &step_plan, const std::string &target_frame) const
template<template< typename...> class Container>
msgs::ErrorStatus transform (Container< msgs::Step > &cont, const std::string &target_frame) const
template<typename T >
msgs::ErrorStatus transformToPlannerFrame (T &p) const
template<typename T >
msgs::ErrorStatus transformToRobotFrame (T &p) const
 ~FootPoseTransformer ()

Protected Attributes

tf::Transform left_foot_frame_transform
tf::Transform right_foot_frame_transform

Detailed Description

Transforms footstep plans from one frame to another

Definition at line 46 of file foot_pose_transformer.h.


Member Typedef Documentation

Definition at line 83 of file foot_pose_transformer.h.

Definition at line 82 of file foot_pose_transformer.h.


Constructor & Destructor Documentation

Definition at line 5 of file foot_pose_transformer.cpp.

Definition at line 30 of file foot_pose_transformer.cpp.


Member Function Documentation

msgs::ErrorStatus vigir_footstep_planning::FootPoseTransformer::transform ( geometry_msgs::Pose pose,
const tf::Transform transform 
) const

Definition at line 34 of file foot_pose_transformer.cpp.

msgs::ErrorStatus vigir_footstep_planning::FootPoseTransformer::transform ( msgs::Foot &  foot,
const std::string &  target_frame 
) const

Definition at line 43 of file foot_pose_transformer.cpp.

msgs::ErrorStatus vigir_footstep_planning::FootPoseTransformer::transform ( msgs::Feet &  feet,
const std::string &  target_frame 
) const

Definition at line 56 of file foot_pose_transformer.cpp.

msgs::ErrorStatus vigir_footstep_planning::FootPoseTransformer::transform ( msgs::Step &  step,
const std::string &  target_frame 
) const

Definition at line 64 of file foot_pose_transformer.cpp.

msgs::ErrorStatus vigir_footstep_planning::FootPoseTransformer::transform ( msgs::StepPlan &  step_plan,
const std::string &  target_frame 
) const

Definition at line 69 of file foot_pose_transformer.cpp.

template<template< typename...> class Container>
msgs::ErrorStatus vigir_footstep_planning::FootPoseTransformer::transform ( Container< msgs::Step > &  cont,
const std::string &  target_frame 
) const [inline]

Definition at line 60 of file foot_pose_transformer.h.

template<typename T >
msgs::ErrorStatus vigir_footstep_planning::FootPoseTransformer::transformToPlannerFrame ( T p) const [inline]

Definition at line 70 of file foot_pose_transformer.h.

template<typename T >
msgs::ErrorStatus vigir_footstep_planning::FootPoseTransformer::transformToRobotFrame ( T p) const [inline]

Definition at line 76 of file foot_pose_transformer.h.


Member Data Documentation

Definition at line 87 of file foot_pose_transformer.h.

Definition at line 88 of file foot_pose_transformer.h.


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


vigir_foot_pose_transformer
Author(s): Alexander Stumpf
autogenerated on Fri Apr 7 2017 02:59:34