#include <pose_helper.hpp>
|
| 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 () |
| |
Definition at line 34 of file pose_helper.hpp.
◆ PoseHelper()
| directSearchWS::PoseHelper::PoseHelper |
( |
| ) |
|
|
private |
◆ calcAngularDistanceInRad()
◆ calcDistPositionEucl()
◆ calcDistPositionWithNBV()
◆ calculateDistance()
◆ calculateViewCenterPoint()
| Eigen::Vector3d directSearchWS::PoseHelper::calculateViewCenterPoint |
( |
const geometry_msgs::Pose & |
pose | ) |
|
|
private |
◆ checkOrientationsAreApproxEquale()
◆ checkPosesAreApproxEquale()
| bool directSearchWS::PoseHelper::checkPosesAreApproxEquale |
( |
const geometry_msgs::Pose & |
pose1, |
|
|
const geometry_msgs::Pose & |
pose2, |
|
|
const double |
positionThreshold, |
|
|
const double |
orientationRadThreshold |
|
) |
| |
◆ checkPositionsAreApproxEquale()
◆ checkViewCenterPointsAreApproxEquale()
◆ convertPoseQuatToQuat()
| Eigen::Quaterniond directSearchWS::PoseHelper::convertPoseQuatToQuat |
( |
const geometry_msgs::Pose & |
pose | ) |
|
|
inlineprivate |
◆ convertPositionToVec()
| Eigen::Vector3d directSearchWS::PoseHelper::convertPositionToVec |
( |
const geometry_msgs::Pose & |
pose | ) |
|
|
inlineprivate |
◆ convertVecToPosition()
| geometry_msgs::Pose directSearchWS::PoseHelper::convertVecToPosition |
( |
const Eigen::Vector3d & |
vec | ) |
|
|
inlineprivate |
◆ getCurrentCameraPose()
◆ getCurrentRobotPose()
◆ getInstance()
◆ getOriginPose()
◆ resetInstance()
| void directSearchWS::PoseHelper::resetInstance |
( |
| ) |
|
|
static |
◆ waitForParam()
template<typename T >
| T directSearchWS::PoseHelper::waitForParam |
( |
ros::NodeHandle |
n, |
|
|
std::string |
param |
|
) |
| |
|
staticprivate |
◆ distanceFuncParam
| int directSearchWS::PoseHelper::distanceFuncParam |
|
staticprivate |
◆ getCameraPoseServiceClient
◆ getDistanceServiceClient
◆ getRobotPoseServiceClient
◆ instancePtr
◆ viewCenterOrientationRadDistanceThreshold
| double directSearchWS::PoseHelper::viewCenterOrientationRadDistanceThreshold |
|
staticprivate |
◆ viewCenterPositionDistanceThreshold
| double directSearchWS::PoseHelper::viewCenterPositionDistanceThreshold |
|
staticprivate |
◆ viewPointDistance
| double directSearchWS::PoseHelper::viewPointDistance |
|
staticprivate |
The documentation for this class was generated from the following files: