#include <pose_helper.hpp>
Public Member Functions | |
double | calcAngularDistanceInRad (const geometry_msgs::Pose &pose1, const geometry_msgs::Pose &pose2) |
double | calculateDistance (const geometry_msgs::Pose &pose1, const geometry_msgs::Pose &pose2) |
bool | checkOrientationsAreApproxEquale (const geometry_msgs::Pose &pose1, const geometry_msgs::Pose &pose2, const double orientationRadThreshold) |
bool | checkPosesAreApproxEquale (const geometry_msgs::Pose &pose1, const geometry_msgs::Pose &pose2, const double positionThreshold, const double orientationRadThreshold) |
bool | checkPositionsAreApproxEquale (const geometry_msgs::Pose &pose1, const geometry_msgs::Pose &pose2, const double positionThreshold) |
bool | checkViewCenterPointsAreApproxEquale (const geometry_msgs::Pose &pose1, const geometry_msgs::Pose &pose2) |
geometry_msgs::Pose | getCurrentCameraPose () |
geometry_msgs::Pose | getCurrentRobotPose () |
Static Public Member Functions | |
static boost::shared_ptr< PoseHelper > | getInstance () |
static void | resetInstance () |
Private Member Functions | |
double | calcDistPositionEucl (const geometry_msgs::Pose &pose1, const geometry_msgs::Pose &pose2) |
double | calcDistPositionWithNBV (const geometry_msgs::Pose &pose1, const geometry_msgs::Pose &pose2) |
Eigen::Vector3d | calculateViewCenterPoint (const geometry_msgs::Pose &pose) |
Eigen::Quaterniond | convertPoseQuatToQuat (const geometry_msgs::Pose &pose) |
Eigen::Vector3d | convertPositionToVec (const geometry_msgs::Pose &pose) |
geometry_msgs::Pose | convertVecToPosition (const Eigen::Vector3d &vec) |
geometry_msgs::Pose | getOriginPose () |
PoseHelper () | |
Static Private Member Functions | |
template<typename T > | |
static T | waitForParam (ros::NodeHandle n, std::string param) |
Private Attributes | |
ros::ServiceClient | getCameraPoseServiceClient |
ros::ServiceClient | getDistanceServiceClient |
ros::ServiceClient | getRobotPoseServiceClient |
Static Private Attributes | |
static int | distanceFuncParam |
static boost::shared_ptr< PoseHelper > | instancePtr |
static double | viewCenterOrientationRadDistanceThreshold |
static double | viewCenterPositionDistanceThreshold |
static double | viewPointDistance |
Definition at line 34 of file pose_helper.hpp.
|
private |
Definition at line 69 of file pose_helper.cpp.
double directSearchWS::PoseHelper::calcAngularDistanceInRad | ( | const geometry_msgs::Pose & | pose1, |
const geometry_msgs::Pose & | pose2 | ||
) |
Definition at line 99 of file pose_helper.cpp.
|
private |
Definition at line 93 of file pose_helper.cpp.
|
private |
Definition at line 77 of file pose_helper.cpp.
double directSearchWS::PoseHelper::calculateDistance | ( | const geometry_msgs::Pose & | pose1, |
const geometry_msgs::Pose & | pose2 | ||
) |
Definition at line 137 of file pose_helper.cpp.
|
private |
Definition at line 107 of file pose_helper.cpp.
bool directSearchWS::PoseHelper::checkOrientationsAreApproxEquale | ( | const geometry_msgs::Pose & | pose1, |
const geometry_msgs::Pose & | pose2, | ||
const double | orientationRadThreshold | ||
) |
Definition at line 164 of file pose_helper.cpp.
bool directSearchWS::PoseHelper::checkPosesAreApproxEquale | ( | const geometry_msgs::Pose & | pose1, |
const geometry_msgs::Pose & | pose2, | ||
const double | positionThreshold, | ||
const double | orientationRadThreshold | ||
) |
Definition at line 153 of file pose_helper.cpp.
bool directSearchWS::PoseHelper::checkPositionsAreApproxEquale | ( | const geometry_msgs::Pose & | pose1, |
const geometry_msgs::Pose & | pose2, | ||
const double | positionThreshold | ||
) |
Definition at line 159 of file pose_helper.cpp.
bool directSearchWS::PoseHelper::checkViewCenterPointsAreApproxEquale | ( | const geometry_msgs::Pose & | pose1, |
const geometry_msgs::Pose & | pose2 | ||
) |
Definition at line 145 of file pose_helper.cpp.
|
inlineprivate |
Definition at line 69 of file pose_helper.hpp.
|
inlineprivate |
Definition at line 57 of file pose_helper.hpp.
|
inlineprivate |
Definition at line 61 of file pose_helper.hpp.
geometry_msgs::Pose directSearchWS::PoseHelper::getCurrentCameraPose | ( | ) |
Definition at line 126 of file pose_helper.cpp.
geometry_msgs::Pose directSearchWS::PoseHelper::getCurrentRobotPose | ( | ) |
Definition at line 115 of file pose_helper.cpp.
|
static |
Definition at line 28 of file pose_helper.cpp.
|
inlineprivate |
Definition at line 73 of file pose_helper.hpp.
|
static |
Definition at line 36 of file pose_helper.cpp.
|
staticprivate |
Definition at line 57 of file pose_helper.cpp.
|
staticprivate |
Definition at line 39 of file pose_helper.hpp.
|
private |
Definition at line 45 of file pose_helper.hpp.
|
private |
Definition at line 43 of file pose_helper.hpp.
|
private |
Definition at line 44 of file pose_helper.hpp.
|
staticprivate |
Definition at line 37 of file pose_helper.hpp.
|
staticprivate |
Definition at line 41 of file pose_helper.hpp.
|
staticprivate |
Definition at line 40 of file pose_helper.hpp.
|
staticprivate |
Definition at line 38 of file pose_helper.hpp.