Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove unused hand property from MTC tutorial #420

Merged
merged 2 commits into from
Jun 6, 2022
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -670,9 +670,9 @@ This next block of code creates a ``SerialContainer``. This is a container that

{
auto grasp = std::make_unique<mtc::SerialContainer>("pick object");
task.properties().exposeTo(grasp->properties(), { "eef", "hand", "group", "ik_frame" });
task.properties().exposeTo(grasp->properties(), { "eef", "group", "ik_frame" });
grasp->properties().configureInitFrom(mtc::Stage::PARENT,
{ "eef", "hand", "group", "ik_frame" });
{ "eef", "group", "ik_frame" });



Expand Down Expand Up @@ -827,9 +827,9 @@ We also create a serial container for the place stages. This is done similarly t

{
auto place = std::make_unique<mtc::SerialContainer>("place object");
task.properties().exposeTo(place->properties(), { "eef", "hand", "group", "ik_frame" });
task.properties().exposeTo(place->properties(), { "eef", "group", "ik_frame" });
place->properties().configureInitFrom(mtc::Stage::PARENT,
{ "eef", "hand", "group", "ik_frame" });
{ "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``. 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 Down
Original file line number Diff line number Diff line change
Expand Up @@ -149,10 +149,10 @@ mtc::Task MTCTaskNode::createTask()
// In fact, `task` itself is a SerialContainer by default.
{
auto grasp = std::make_unique<mtc::SerialContainer>("pick object");
task.properties().exposeTo(grasp->properties(), { "eef", "hand", "group", "ik_frame" });
task.properties().exposeTo(grasp->properties(), { "eef", "group", "ik_frame" });
// clang-format off
grasp->properties().configureInitFrom(mtc::Stage::PARENT,
{ "eef", "hand", "group", "ik_frame" });
{ "eef", "group", "ik_frame" });
// clang-format on

{
Expand Down Expand Up @@ -268,10 +268,10 @@ mtc::Task MTCTaskNode::createTask()

{
auto place = std::make_unique<mtc::SerialContainer>("place object");
task.properties().exposeTo(place->properties(), { "eef", "hand", "group", "ik_frame" });
task.properties().exposeTo(place->properties(), { "eef", "group", "ik_frame" });
// clang-format off
place->properties().configureInitFrom(mtc::Stage::PARENT,
{ "eef", "hand", "group", "ik_frame" });
{ "eef", "group", "ik_frame" });
// clang-format on

/****************************************************
Expand Down