Skip to content

Commit 35048cb

Browse files
authored
Fix place pose generation IK frame in MTC Tutorial (#727)
1 parent f226955 commit 35048cb

File tree

2 files changed

+10
-3
lines changed

2 files changed

+10
-3
lines changed

doc/tutorials/pick_and_place_with_moveit_task_constructor/pick_and_place_with_moveit_task_constructor.rst

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -166,6 +166,7 @@ Open ``mtc_node.cpp`` in your editor of choice, and paste in the following code.
166166
geometry_msgs::msg::Pose pose;
167167
pose.position.x = 0.5;
168168
pose.position.y = -0.25;
169+
pose.orientation.w = 1.0;
169170
object.pose = pose;
170171

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

809-
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``.
810+
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.
811+
We start by creating a stage to generate the poses and inheriting the task properties.
812+
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.
813+
We then pass the target pose to the stage with ``setPose``.
810814
Next, we use ``setMonitoredStage`` and pass it the pointer to the ``attach_object`` stage from earlier.
811815
This allows the stage to know how the object is attached.
812816
We then create a ``ComputeIK`` stage and pass it our ``GeneratePlacePose`` stage - the rest follows the same logic as above with the pick stages.
@@ -823,6 +827,7 @@ We then create a ``ComputeIK`` stage and pass it our ``GeneratePlacePose`` stage
823827
geometry_msgs::msg::PoseStamped target_pose_msg;
824828
target_pose_msg.header.frame_id = "object";
825829
target_pose_msg.pose.position.y = 0.5;
830+
target_pose_msg.pose.orientation.w = 1.0;
826831
stage->setPose(target_pose_msg);
827832
stage->setMonitoredStage(attach_object_stage); // Hook into attach_object_stage
828833

@@ -831,7 +836,7 @@ We then create a ``ComputeIK`` stage and pass it our ``GeneratePlacePose`` stage
831836
std::make_unique<mtc::stages::ComputeIK>("place pose IK", std::move(stage));
832837
wrapper->setMaxIKSolutions(2);
833838
wrapper->setMinSolutionDistance(1.0);
834-
wrapper->setIKFrame(hand_frame);
839+
wrapper->setIKFrame("object");
835840
wrapper->properties().configureInitFrom(mtc::Stage::PARENT, { "eef", "group" });
836841
wrapper->properties().configureInitFrom(mtc::Stage::INTERFACE, { "target_pose" });
837842
place->insert(std::move(wrapper));

doc/tutorials/pick_and_place_with_moveit_task_constructor/src/mtc_node.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,7 @@ void MTCTaskNode::setupPlanningScene()
5858
geometry_msgs::msg::Pose pose;
5959
pose.position.x = 0.5;
6060
pose.position.y = -0.25;
61+
pose.orientation.w = 1.0;
6162
object.pose = pose;
6263

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

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

0 commit comments

Comments
 (0)