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

Add task_name to InitializeMTCTask #31

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
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
2 changes: 1 addition & 1 deletion examples/bt_allow_collisions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ static const char* xml_text = R"(
collision_object="{cylinder}" />
<AddObjectToPlanningScene planning_scene_interface="{psi}"
collision_object="{cylinder}"/>
<InitializeMTCTask task="{mtc_task}" />
<InitializeMTCTask task="{mtc_task}" task_name="allow_collisions" />
<CreateMTCPipelinePlanner pipeline_id="ompl"
planner_id="RRTConnect"
solver="{rrt_connect}"
Expand Down
2 changes: 1 addition & 1 deletion examples/bt_compute_ik.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ static const char* xml_text = R"(
collision_object="{cylinder}" />
<AddObjectToPlanningScene planning_scene_interface="{psi}"
collision_object="{cylinder}"/>
<InitializeMTCTask task="{mtc_task}" />
<InitializeMTCTask task="{mtc_task}" task_name="compute_ik" />
<CreateMTCPipelinePlanner pipeline_id="ompl"
planner_id="RRTConnect"
solver="{rrt_connect}"
Expand Down
2 changes: 1 addition & 1 deletion examples/bt_demo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ static const char* xml_text = R"(

<BehaviorTree ID="MainTree">
<Sequence name="root">
<InitializeMTCTask task="{mtc_task}" />
<InitializeMTCTask task="{mtc_task}" task_name="demo" />
<CreateMTCCurrentState stage="{stage}" />
<MoveMTCStageToTask child="{stage}" parent="{mtc_task}" />
<PlanMTCTask task="{mtc_task}" max_solutions="5" />
Expand Down
2 changes: 1 addition & 1 deletion examples/bt_generate_place_pose.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ static const char* xml_text = R"(
collision_object="{cylinder}" />
<AddObjectToPlanningScene planning_scene_interface="{psi}"
collision_object="{cylinder}"/>
<InitializeMTCTask task="{mtc_task}" />
<InitializeMTCTask task="{mtc_task}" task_name="generate_place_pose" />
<CreateMTCPipelinePlanner pipeline_id="ompl"
planner_id="RRTConnect"
solver="{rrt_connect}"
Expand Down
2 changes: 1 addition & 1 deletion examples/bt_joint_interpolation_solver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ static const char* xml_text = R"(

<BehaviorTree ID="MainTree">
<Sequence name="root">
<InitializeMTCTask task="{mtc_task}" />
<InitializeMTCTask task="{mtc_task}" task_name="joint_interpolation_solver" />
<CreateMTCJointInterpolation solver="{joint_solver}" />
<CreateMTCCurrentState stage="{stage}" />
<MoveMTCStageToTask child="{stage}" parent="{mtc_task}" />
Expand Down
2 changes: 1 addition & 1 deletion examples/bt_move_relative.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ static const char* xml_text = R"(

<BehaviorTree ID="MainTree">
<Sequence name="root">
<InitializeMTCTask task="{mtc_task}" />
<InitializeMTCTask task="{mtc_task}" task_name="move_relative" />
<CreateMTCPipelinePlanner pipeline_id="ompl"
planner_id="RRTConnect"
solver="{rrt_connect}" />
Expand Down
2 changes: 1 addition & 1 deletion examples/bt_move_to.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ static const char* xml_text = R"(

<BehaviorTree ID="MainTree">
<Sequence name="root">
<InitializeMTCTask task="{mtc_task}" />
<InitializeMTCTask task="{mtc_task}" task_name="move_to" />
<CreateMTCPipelinePlanner pipeline_id="ompl"
planner_id="RRTConnect"
solver="{rrt_connect}"/>
Expand Down
2 changes: 1 addition & 1 deletion examples/bt_pick_place.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ static const char* xml_text = R"(
<AddObjectToPlanningScene planning_scene_interface="{psi}" collision_object="{cylinder}" />

<!-- Create Task -->
<InitializeMTCTask task="{mtc_task}" />
<InitializeMTCTask task="{mtc_task}" task_name="pick_place" />

<!-- Add properpties to the Task -->
<SetMTCTaskPropertyString stage="{mtc_task}" property_name="eef" property="{eef}" />
Expand Down
2 changes: 1 addition & 1 deletion examples/bt_serial_container.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ static const char* xml_text = R"(

<BehaviorTree ID="MainTree">
<Sequence name="root">
<InitializeMTCTask task="{mtc_task}" />
<InitializeMTCTask task="{mtc_task}" task_name="serial_container" />
<CreateMTCPipelinePlanner pipeline_id="ompl"
planner_id="RRTConnect"
solver="{rrt_connect}" />
Expand Down
7 changes: 7 additions & 0 deletions src/initialize_mtc_task.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,13 @@ InitializeMTCTask::InitializeMTCTask(const std::string& name,

BT::NodeStatus InitializeMTCTask::tick()
{
std::string task_name;

if(!getInput("task_name", task_name))
return NodeStatus::FAILURE;

auto task = std::make_shared<moveit::task_constructor::Task>();
task->setName(task_name);
task->loadRobotModel();

setOutput("task", task);
Expand All @@ -25,6 +31,7 @@ BT::PortsList InitializeMTCTask::providedPorts()
return {
BT::OutputPort<moveit::task_constructor::TaskPtr>("task", "{mtc_task}",
"MoveIt Task Constructor task."),
BT::InputPort<std::string>("task_name", "task pipeline", "MoveIt Task Constructor task name.")
};
}

Expand Down