Functions | |
void | moveit::planning_interface::MoveGroup::clearPoseTarget (const std::string &end_effector_link="") |
Forget pose specified for the end-effector end_effector_link. | |
void | moveit::planning_interface::MoveGroup::clearPoseTargets () |
Forget any poses specified for any end-effector. | |
const std::string & | moveit::planning_interface::MoveGroup::getEndEffector () const |
Get the current end-effector name. This returns the value set by setEndEffector(). If setEndEffector() was not called, this function reports an end-effector attached to this group. If there are multiple end-effectors, one of them is returned. If no end-effector is known, the empty string is returned. | |
const std::string & | moveit::planning_interface::MoveGroup::getEndEffectorLink () const |
Get the current end-effector link. This returns the value set by setEndEffectorLink(). If setEndEffectorLink() was not called, this function reports the link name that serves as parent of an end-effector attached to this group. If there are multiple end-effectors, one of them is returned. If no such link is known, the empty string is returned. | |
const std::string & | moveit::planning_interface::MoveGroup::getPoseReferenceFrame () const |
Get the reference frame set by setPoseReferenceFrame(). By default this is the reference frame of the robot model. | |
const geometry_msgs::PoseStamped & | moveit::planning_interface::MoveGroup::getPoseTarget (const std::string &end_effector_link="") const |
const std::vector < geometry_msgs::PoseStamped > & | moveit::planning_interface::MoveGroup::getPoseTargets (const std::string &end_effector_link="") const |
bool | moveit::planning_interface::MoveGroup::setEndEffector (const std::string &eef_name) |
Specify the name of the end-effector to use. | |
bool | moveit::planning_interface::MoveGroup::setEndEffectorLink (const std::string &link_name) |
Specify the link the end-effector to be considered is attached to. | |
bool | moveit::planning_interface::MoveGroup::setOrientationTarget (double x, double y, double z, double w, const std::string &end_effector_link="") |
Set the goal orientation of the end-effector end_effector_link to be the quaternion (x,y,z,w). If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. | |
void | moveit::planning_interface::MoveGroup::setPoseReferenceFrame (const std::string &pose_reference_frame) |
Specify which reference frame to assume for poses specified without a reference frame. | |
bool | moveit::planning_interface::MoveGroup::setPoseTarget (const Eigen::Affine3d &end_effector_pose, const std::string &end_effector_link="") |
Set the goal pose of the end-effector end_effector_link. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. | |
bool | moveit::planning_interface::MoveGroup::setPoseTarget (const geometry_msgs::Pose &target, const std::string &end_effector_link="") |
Set the goal pose of the end-effector end_effector_link. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. | |
bool | moveit::planning_interface::MoveGroup::setPoseTarget (const geometry_msgs::PoseStamped &target, const std::string &end_effector_link="") |
Set the goal pose of the end-effector end_effector_link. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. | |
bool | moveit::planning_interface::MoveGroup::setPoseTargets (const EigenSTL::vector_Affine3d &end_effector_pose, const std::string &end_effector_link="") |
Set the goal pose of the end-effector end_effector_link. In this case the goal pose can be any of the ones specified in the array. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. | |
bool | moveit::planning_interface::MoveGroup::setPoseTargets (const std::vector< geometry_msgs::Pose > &target, const std::string &end_effector_link="") |
Set the goal pose of the end-effector end_effector_link. In this case the goal pose can be any of the ones specified in the array. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. | |
bool | moveit::planning_interface::MoveGroup::setPoseTargets (const std::vector< geometry_msgs::PoseStamped > &target, const std::string &end_effector_link="") |
Set the goal pose of the end-effector end_effector_link. In this case the goal pose can be any of the ones specified in the array. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. | |
bool | moveit::planning_interface::MoveGroup::setPositionTarget (double x, double y, double z, const std::string &end_effector_link="") |
Set the goal position of the end-effector end_effector_link to be (x, y, z). If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. | |
bool | moveit::planning_interface::MoveGroup::setRPYTarget (double roll, double pitch, double yaw, const std::string &end_effector_link="") |
Set the goal orientation of the end-effector end_effector_link to be (roll,pitch,yaw) radians. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed. |
void moveit::planning_interface::MoveGroup::clearPoseTarget | ( | const std::string & | end_effector_link = "" | ) |
Forget pose specified for the end-effector end_effector_link.
Definition at line 1069 of file move_group.cpp.
Forget any poses specified for any end-effector.
Definition at line 1074 of file move_group.cpp.
const std::string & moveit::planning_interface::MoveGroup::getEndEffector | ( | ) | const |
Get the current end-effector name. This returns the value set by setEndEffector(). If setEndEffector() was not called, this function reports an end-effector attached to this group. If there are multiple end-effectors, one of them is returned. If no end-effector is known, the empty string is returned.
Definition at line 1047 of file move_group.cpp.
const std::string & moveit::planning_interface::MoveGroup::getEndEffectorLink | ( | ) | const |
Get the current end-effector link. This returns the value set by setEndEffectorLink(). If setEndEffectorLink() was not called, this function reports the link name that serves as parent of an end-effector attached to this group. If there are multiple end-effectors, one of them is returned. If no such link is known, the empty string is returned.
Definition at line 1042 of file move_group.cpp.
const std::string & moveit::planning_interface::MoveGroup::getPoseReferenceFrame | ( | ) | const |
Get the reference frame set by setPoseReferenceFrame(). By default this is the reference frame of the robot model.
Definition at line 1250 of file move_group.cpp.
const geometry_msgs::PoseStamped & moveit::planning_interface::MoveGroup::getPoseTarget | ( | const std::string & | end_effector_link = "" | ) | const |
Get the currently set pose goal for the end-effector end_effector_link. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed
Definition at line 1145 of file move_group.cpp.
const std::vector< geometry_msgs::PoseStamped > & moveit::planning_interface::MoveGroup::getPoseTargets | ( | const std::string & | end_effector_link = "" | ) | const |
Get the currently set pose goal for the end-effector end_effector_link. The pose goal can consist of multiple poses, if corresponding setPoseTarget() calls were made. Otherwise, only one pose is returned in the vector. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed
Definition at line 1150 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::setEndEffector | ( | const std::string & | eef_name | ) |
Specify the name of the end-effector to use.
Definition at line 1061 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::setEndEffectorLink | ( | const std::string & | link_name | ) |
Specify the link the end-effector to be considered is attached to.
Definition at line 1052 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::setOrientationTarget | ( | double | x, |
double | y, | ||
double | z, | ||
double | w, | ||
const std::string & | end_effector_link = "" |
||
) |
Set the goal orientation of the end-effector end_effector_link to be the quaternion (x,y,z,w). If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed.
Definition at line 1220 of file move_group.cpp.
void moveit::planning_interface::MoveGroup::setPoseReferenceFrame | ( | const std::string & | pose_reference_frame | ) |
Specify which reference frame to assume for poses specified without a reference frame.
Definition at line 1245 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::setPoseTarget | ( | const Eigen::Affine3d & | end_effector_pose, |
const std::string & | end_effector_link = "" |
||
) |
Set the goal pose of the end-effector end_effector_link. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed.
Definition at line 1079 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::setPoseTarget | ( | const geometry_msgs::Pose & | target, |
const std::string & | end_effector_link = "" |
||
) |
Set the goal pose of the end-effector end_effector_link. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed.
Definition at line 1088 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::setPoseTarget | ( | const geometry_msgs::PoseStamped & | target, |
const std::string & | end_effector_link = "" |
||
) |
Set the goal pose of the end-effector end_effector_link. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed.
Definition at line 1097 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::setPoseTargets | ( | const EigenSTL::vector_Affine3d & | end_effector_pose, |
const std::string & | end_effector_link = "" |
||
) |
Set the goal pose of the end-effector end_effector_link. In this case the goal pose can be any of the ones specified in the array. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed.
Definition at line 1103 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::setPoseTargets | ( | const std::vector< geometry_msgs::Pose > & | target, |
const std::string & | end_effector_link = "" |
||
) |
Set the goal pose of the end-effector end_effector_link. In this case the goal pose can be any of the ones specified in the array. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed.
Definition at line 1117 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::setPoseTargets | ( | const std::vector< geometry_msgs::PoseStamped > & | target, |
const std::string & | end_effector_link = "" |
||
) |
Set the goal pose of the end-effector end_effector_link. In this case the goal pose can be any of the ones specified in the array. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed.
Definition at line 1131 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::setPositionTarget | ( | double | x, |
double | y, | ||
double | z, | ||
const std::string & | end_effector_link = "" |
||
) |
Set the goal position of the end-effector end_effector_link to be (x, y, z). If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed.
Definition at line 1173 of file move_group.cpp.
bool moveit::planning_interface::MoveGroup::setRPYTarget | ( | double | roll, |
double | pitch, | ||
double | yaw, | ||
const std::string & | end_effector_link = "" |
||
) |
Set the goal orientation of the end-effector end_effector_link to be (roll,pitch,yaw) radians. If end_effector_link is empty (the default value) then the end-effector reported by getEndEffectorLink() is assumed.
Definition at line 1198 of file move_group.cpp.