Public Types | Public Member Functions | Static Public Member Functions
moveit_object_handling::MoveItHelpers Class Reference

#include <MoveItHelpers.h>

List of all members.

Public Types

typedef boost::shared_ptr
< moveit_msgs::PositionConstraint > 
PositionConstraintPtr
typedef boost::shared_ptr
< shape_msgs::SolidPrimitive > 
SolidPrimitivePtr

Public Member Functions

 MoveItHelpers ()
 ~MoveItHelpers ()

Static Public Member Functions

static
moveit_msgs::PositionConstraint 
getBoxConstraint (const std::string &link_name, const geometry_msgs::PoseStamped &boxOrigin, const double &x, const double &y, const double &z)
static SolidPrimitivePtr getConeBV (const Eigen::Vector3d &_fromPose, const Eigen::Quaterniond &_fromOrientation, const Eigen::Vector3d &_direction, const double &radius_start, const double &radius_end, Eigen::Vector3d &bv_pose, Eigen::Quaterniond &bv_orientation)
static SolidPrimitivePtr getCylinderBV (const Eigen::Vector3d &_fromPose, const Eigen::Quaterniond &_fromOrientation, const Eigen::Vector3d &_direction, const double &radius, Eigen::Vector3d &bv_pose, Eigen::Quaterniond &bv_orientation)
static moveit_msgs::Constraints getJointConstraint (const std::string &link_name, const sensor_msgs::JointState &joint_state, const float &joint_tolerance)
static
moveit_msgs::OrientationConstraint 
getOrientationConstraint (const std::string &link_name, const geometry_msgs::QuaternionStamped &quat, const float &x_tolerance, const float &y_tolerance, const float &z_tolerance)
static moveit_msgs::Constraints getPoseConstraint (const std::string &link_name, const geometry_msgs::PoseStamped &pose, double tolerance_pos, double tolerance_angle, int type)
static PositionConstraintPtr getSpherePoseConstraint (const std::string &link_name, const geometry_msgs::PoseStamped &target_pose, float maxArmReachDistance)

Detailed Description

Definition at line 17 of file MoveItHelpers.h.


Member Typedef Documentation

typedef boost::shared_ptr<moveit_msgs::PositionConstraint> moveit_object_handling::MoveItHelpers::PositionConstraintPtr

Definition at line 21 of file MoveItHelpers.h.

typedef boost::shared_ptr<shape_msgs::SolidPrimitive> moveit_object_handling::MoveItHelpers::SolidPrimitivePtr

Definition at line 22 of file MoveItHelpers.h.


Constructor & Destructor Documentation

Definition at line 26 of file MoveItHelpers.h.

Definition at line 28 of file MoveItHelpers.h.


Member Function Documentation

moveit_msgs::PositionConstraint moveit_object_handling::MoveItHelpers::getBoxConstraint ( const std::string &  link_name,
const geometry_msgs::PoseStamped &  boxOrigin,
const double &  x,
const double &  y,
const double &  z 
) [static]
Parameters:
boxOrginthe origin of the box

Definition at line 60 of file MoveItHelpers.cpp.

moveit_object_handling::MoveItHelpers::SolidPrimitivePtr moveit_object_handling::MoveItHelpers::getConeBV ( const Eigen::Vector3d &  _fromPose,
const Eigen::Quaterniond &  _fromOrientation,
const Eigen::Vector3d &  _direction,
const double &  radius_start,
const double &  radius_end,
Eigen::Vector3d &  bv_pose,
Eigen::Quaterniond &  bv_orientation 
) [static]

Like getCylinderConstraint() with two input stamped poses, but here 'dir' is specified relative to from, it is a moving direction, not a position. returns a constraint with a cone which at <from> has radius <radius_start>, and goes along <dir>, where it has radius <radius_end>.

Definition at line 204 of file MoveItHelpers.cpp.

moveit_object_handling::MoveItHelpers::SolidPrimitivePtr moveit_object_handling::MoveItHelpers::getCylinderBV ( const Eigen::Vector3d &  _fromPose,
const Eigen::Quaterniond &  _fromOrientation,
const Eigen::Vector3d &  _direction,
const double &  radius,
Eigen::Vector3d &  bv_pose,
Eigen::Quaterniond &  bv_orientation 
) [static]

Definition at line 114 of file MoveItHelpers.cpp.

moveit_msgs::Constraints moveit_object_handling::MoveItHelpers::getJointConstraint ( const std::string &  link_name,
const sensor_msgs::JointState &  joint_state,
const float &  joint_tolerance 
) [static]

Gets the joint constraint such that it corresponds to the passed joint_state

Definition at line 365 of file MoveItHelpers.cpp.

moveit_msgs::OrientationConstraint moveit_object_handling::MoveItHelpers::getOrientationConstraint ( const std::string &  link_name,
const geometry_msgs::QuaternionStamped &  quat,
const float &  x_tolerance,
const float &  y_tolerance,
const float &  z_tolerance 
) [static]

Definition at line 385 of file MoveItHelpers.cpp.

moveit_msgs::Constraints moveit_object_handling::MoveItHelpers::getPoseConstraint ( const std::string &  link_name,
const geometry_msgs::PoseStamped &  pose,
double  tolerance_pos,
double  tolerance_angle,
int  type 
) [static]

Adds goal constraints for the link to be at this pose.

Parameters:
typeif 0, only position is considered. If 1, position and orientation are considered, and if 2 then only orientation is considered.

Definition at line 531 of file MoveItHelpers.cpp.

moveit_object_handling::MoveItHelpers::PositionConstraintPtr moveit_object_handling::MoveItHelpers::getSpherePoseConstraint ( const std::string &  link_name,
const geometry_msgs::PoseStamped &  target_pose,
float  maxArmReachDistance 
) [static]
Parameters:
maxArmReachDistancethe maximum distance the arm can reach (radius of the reaching sphere). Can be an overestimation of it, but should not underestimate.
maxArmReachDistancethe maximum distance the arm can reach (radius of the reaching sphere). Can be an overestimation of it, but should not underestimate.

Definition at line 402 of file MoveItHelpers.cpp.


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


moveit_object_handling
Author(s): Jennifer Buehler
autogenerated on Sat Mar 2 2019 03:50:51