Skip to content

Commit

Permalink
Fix place pose generation IK frame in MTC Tutorial (#727)
Browse files Browse the repository at this point in the history
  • Loading branch information
sea-bass committed Aug 8, 2023
1 parent f226955 commit 35048cb
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -166,6 +166,7 @@ Open ``mtc_node.cpp`` in your editor of choice, and paste in the following code.
geometry_msgs::msg::Pose pose;
pose.position.x = 0.5;
pose.position.y = -0.25;
pose.orientation.w = 1.0;
object.pose = pose;

moveit::planning_interface::PlanningSceneInterface psi;
Expand Down Expand Up @@ -806,7 +807,10 @@ The next stages will be added to the serial container rather than the task.
place->properties().configureInitFrom(mtc::Stage::PARENT,
{ "eef", "group", "ik_frame" });

This next stage generates the poses used to place the object and compute the inverse kinematics for those poses - it is somewhat similar to the ``generate grasp pose`` stage from the pick serial container. We start by creating a stage to generate the poses and inheriting the task properties. We specify the pose where we want to place the object with a ``PoseStamped`` message from ``geometry_msgs`` - in this case, we choose ``y = 0.5``. We then pass the target pose to the stage with ``setPose``.
This next stage generates the poses used to place the object and compute the inverse kinematics for those poses - it is somewhat similar to the ``generate grasp pose`` stage from the pick serial container.
We start by creating a stage to generate the poses and inheriting the task properties.
We specify the pose where we want to place the object with a ``PoseStamped`` message from ``geometry_msgs`` - in this case, we choose ``y = 0.5`` in the ``"object"`` frame.
We then pass the target pose to the stage with ``setPose``.
Next, we use ``setMonitoredStage`` and pass it the pointer to the ``attach_object`` stage from earlier.
This allows the stage to know how the object is attached.
We then create a ``ComputeIK`` stage and pass it our ``GeneratePlacePose`` stage - the rest follows the same logic as above with the pick stages.
Expand All @@ -823,6 +827,7 @@ We then create a ``ComputeIK`` stage and pass it our ``GeneratePlacePose`` stage
geometry_msgs::msg::PoseStamped target_pose_msg;
target_pose_msg.header.frame_id = "object";
target_pose_msg.pose.position.y = 0.5;
target_pose_msg.pose.orientation.w = 1.0;
stage->setPose(target_pose_msg);
stage->setMonitoredStage(attach_object_stage); // Hook into attach_object_stage

Expand All @@ -831,7 +836,7 @@ We then create a ``ComputeIK`` stage and pass it our ``GeneratePlacePose`` stage
std::make_unique<mtc::stages::ComputeIK>("place pose IK", std::move(stage));
wrapper->setMaxIKSolutions(2);
wrapper->setMinSolutionDistance(1.0);
wrapper->setIKFrame(hand_frame);
wrapper->setIKFrame("object");
wrapper->properties().configureInitFrom(mtc::Stage::PARENT, { "eef", "group" });
wrapper->properties().configureInitFrom(mtc::Stage::INTERFACE, { "target_pose" });
place->insert(std::move(wrapper));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@ void MTCTaskNode::setupPlanningScene()
geometry_msgs::msg::Pose pose;
pose.position.x = 0.5;
pose.position.y = -0.25;
pose.orientation.w = 1.0;
object.pose = pose;

moveit::planning_interface::PlanningSceneInterface psi;
Expand Down Expand Up @@ -287,6 +288,7 @@ mtc::Task MTCTaskNode::createTask()
geometry_msgs::msg::PoseStamped target_pose_msg;
target_pose_msg.header.frame_id = "object";
target_pose_msg.pose.position.y = 0.5;
target_pose_msg.pose.orientation.w = 1.0;
stage->setPose(target_pose_msg);
stage->setMonitoredStage(attach_object_stage); // Hook into attach_object_stage

Expand All @@ -297,7 +299,7 @@ mtc::Task MTCTaskNode::createTask()
// clang-format on
wrapper->setMaxIKSolutions(2);
wrapper->setMinSolutionDistance(1.0);
wrapper->setIKFrame(hand_frame);
wrapper->setIKFrame("object");
wrapper->properties().configureInitFrom(mtc::Stage::PARENT, { "eef", "group" });
wrapper->properties().configureInitFrom(mtc::Stage::INTERFACE, { "target_pose" });
place->insert(std::move(wrapper));
Expand Down

0 comments on commit 35048cb

Please sign in to comment.