Public Member Functions | Private Attributes
CartesianControllerUtils Class Reference

#include <cartesian_controller_utils.h>

List of all members.

Public Member Functions

void adjustArrayLength (std::vector< cob_cartesian_controller::PathArray > &m)
 CartesianControllerUtils ()
void copyMatrix (std::vector< double > *path_array, std::vector< cob_cartesian_controller::PathArray > &m)
geometry_msgs::Pose getPose (const std::string &target_frame, const std::string &source_frame)
tf::StampedTransform getStampedTransform (const std::string &target_frame, const std::string &source_frame)
bool inEpsilonArea (const tf::StampedTransform &stamped_transform, const double epsilon)
void poseToRPY (const geometry_msgs::Pose &pose, double &roll, double &pitch, double &yaw)
void previewPath (const geometry_msgs::PoseArray pose_array)
double roundUpToMultiplier (const double numberToRound, const double multiplier)
void transformPose (const std::string source_frame, const std::string target_frame, const geometry_msgs::Pose pose_in, geometry_msgs::Pose &pose_out)

Private Attributes

visualization_msgs::MarkerArray marker_array_
ros::Publisher marker_pub_
ros::NodeHandle nh_
tf::TransformListener tf_listener_

Detailed Description

Definition at line 32 of file cartesian_controller_utils.h.


Constructor & Destructor Documentation

Definition at line 35 of file cartesian_controller_utils.h.


Member Function Documentation

Definition at line 153 of file cartesian_controller_utils.cpp.

void CartesianControllerUtils::copyMatrix ( std::vector< double > *  path_array,
std::vector< cob_cartesian_controller::PathArray > &  m 
)

Definition at line 170 of file cartesian_controller_utils.cpp.

geometry_msgs::Pose CartesianControllerUtils::getPose ( const std::string &  target_frame,
const std::string &  source_frame 
)

Definition at line 23 of file cartesian_controller_utils.cpp.

tf::StampedTransform CartesianControllerUtils::getStampedTransform ( const std::string &  target_frame,
const std::string &  source_frame 
)

Definition at line 36 of file cartesian_controller_utils.cpp.

bool CartesianControllerUtils::inEpsilonArea ( const tf::StampedTransform stamped_transform,
const double  epsilon 
)

Used to check whether the chain_tip_link is close to the target_frame 'stamped_transform' expreses the transform between the two frames. Thus inEpsilonArea() returns 'true' in case 'stamped_transform' is "smaller" than 'epsilon'

Definition at line 89 of file cartesian_controller_utils.cpp.

void CartesianControllerUtils::poseToRPY ( const geometry_msgs::Pose pose,
double &  roll,
double &  pitch,
double &  yaw 
)

Definition at line 115 of file cartesian_controller_utils.cpp.

void CartesianControllerUtils::previewPath ( const geometry_msgs::PoseArray  pose_array)

Definition at line 122 of file cartesian_controller_utils.cpp.

double CartesianControllerUtils::roundUpToMultiplier ( const double  numberToRound,
const double  multiplier 
)

Definition at line 178 of file cartesian_controller_utils.cpp.

void CartesianControllerUtils::transformPose ( const std::string  source_frame,
const std::string  target_frame,
const geometry_msgs::Pose  pose_in,
geometry_msgs::Pose pose_out 
)

Definition at line 60 of file cartesian_controller_utils.cpp.


Member Data Documentation

visualization_msgs::MarkerArray CartesianControllerUtils::marker_array_ [private]

Definition at line 56 of file cartesian_controller_utils.h.

Definition at line 58 of file cartesian_controller_utils.h.

Definition at line 54 of file cartesian_controller_utils.h.

Definition at line 55 of file cartesian_controller_utils.h.


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


cob_cartesian_controller
Author(s): Christoph Mark
autogenerated on Thu Jun 6 2019 21:19:40