Functions
Query current robot state

Functions

std::vector< double > moveit::planning_interface::MoveGroup::getCurrentJointValues ()
 Get the current joint values for the joints planned for by this instance (see getJoints())
geometry_msgs::PoseStamped moveit::planning_interface::MoveGroup::getCurrentPose (const std::string &end_effector_link="")
 Get the pose 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.
std::vector< double > moveit::planning_interface::MoveGroup::getCurrentRPY (const std::string &end_effector_link="")
 Get the roll-pitch-yaw (XYZ) 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.
robot_state::RobotStatePtr moveit::planning_interface::MoveGroup::getCurrentState ()
 Get the current state of the robot.
std::vector< double > moveit::planning_interface::MoveGroup::getRandomJointValues ()
 Get random joint values for the joints planned for by this instance (see getJoints())
geometry_msgs::PoseStamped moveit::planning_interface::MoveGroup::getRandomPose (const std::string &end_effector_link="")
 Get a random reachable pose 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.

Function Documentation

Get the current joint values for the joints planned for by this instance (see getJoints())

Definition at line 1297 of file move_group.cpp.

geometry_msgs::PoseStamped moveit::planning_interface::MoveGroup::getCurrentPose ( const std::string &  end_effector_link = "")

Get the pose 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 1344 of file move_group.cpp.

std::vector< double > moveit::planning_interface::MoveGroup::getCurrentRPY ( const std::string &  end_effector_link = "")

Get the roll-pitch-yaw (XYZ) 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 1368 of file move_group.cpp.

Get the current state of the robot.

Definition at line 1406 of file move_group.cpp.

Get random joint values for the joints planned for by this instance (see getJoints())

Definition at line 1306 of file move_group.cpp.

geometry_msgs::PoseStamped moveit::planning_interface::MoveGroup::getRandomPose ( const std::string &  end_effector_link = "")

Get a random reachable pose 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 1319 of file move_group.cpp.



planning_interface
Author(s): Ioan Sucan
autogenerated on Mon Oct 6 2014 02:33:28