If all you want is the current pose, you can skip MoveIt altogether and get the info directly from TF. The transformation you're looking for is probably base -> right_gripper
. Check out the TF tutorials to see how to get transforms between links.
You only need to use MoveIt for this if you want to get transformations for robot states that are not the current robot state, e.g. to answer the question "what would the transform between base
and right_gripper
be if I executed plan X generated by MoveIt".
Of course you can do it with MoveIt too if you want, something like this:
moveit::planning_interface::MoveGroup group;
// ...
robot_state::RobotStatePtr state = group.getCurrentState();
Eigen::Affine3d &transform = state->getFrameTransform("right_gripper");
See the MoveGroup and RobotState documentation.