Skip to content

Commit 5fce779

Browse files
committed
Update to new Action executor
Signed-off-by: Alberto Tudela <[email protected]>
1 parent 49e478b commit 5fce779

File tree

17 files changed

+82
-66
lines changed

17 files changed

+82
-66
lines changed

plansys2_bt_example/launch/plansys2_bt_example_launch.py

Lines changed: 50 additions & 50 deletions
Original file line numberDiff line numberDiff line change
@@ -39,9 +39,9 @@ def generate_launch_description():
3939
'launch',
4040
'plansys2_bringup_launch_monolithic.py')),
4141
launch_arguments={
42-
'model_file': example_dir + '/pddl/bt_example.pddl',
43-
'namespace': namespace
44-
}.items())
42+
'model_file': example_dir + '/pddl/bt_example.pddl',
43+
'namespace': namespace
44+
}.items())
4545

4646
# Specify the actions
4747
move_1_cmd = Node(
@@ -51,13 +51,13 @@ def generate_launch_description():
5151
namespace=namespace,
5252
output='screen',
5353
parameters=[
54-
example_dir + '/config/params.yaml',
55-
{
56-
'action_name': 'move',
57-
'publisher_port': 1668,
58-
'server_port': 1669,
59-
'bt_xml_file': example_dir + '/behavior_trees_xml/move.xml'
60-
}
54+
example_dir + '/config/params.yaml',
55+
{
56+
'action_name': 'move',
57+
'enable_groot_monitoring': True,
58+
'server_port': 1700,
59+
'bt_xml_file': example_dir + '/behavior_trees_xml/move.xml'
60+
}
6161
])
6262

6363
move_2_cmd = Node(
@@ -67,13 +67,13 @@ def generate_launch_description():
6767
namespace=namespace,
6868
output='screen',
6969
parameters=[
70-
example_dir + '/config/params.yaml',
71-
{
72-
'action_name': 'move',
73-
'publisher_port': 1670,
74-
'server_port': 1671,
75-
'bt_xml_file': example_dir + '/behavior_trees_xml/move.xml'
76-
}
70+
example_dir + '/config/params.yaml',
71+
{
72+
'action_name': 'move',
73+
'enable_groot_monitoring': True,
74+
'server_port': 1700,
75+
'bt_xml_file': example_dir + '/behavior_trees_xml/move.xml'
76+
}
7777
])
7878

7979
move_3_cmd = Node(
@@ -83,13 +83,13 @@ def generate_launch_description():
8383
namespace=namespace,
8484
output='screen',
8585
parameters=[
86-
example_dir + '/config/params.yaml',
87-
{
88-
'action_name': 'move',
89-
'publisher_port': 1672,
90-
'server_port': 1673,
91-
'bt_xml_file': example_dir + '/behavior_trees_xml/move.xml'
92-
}
86+
example_dir + '/config/params.yaml',
87+
{
88+
'action_name': 'move',
89+
'enable_groot_monitoring': True,
90+
'server_port': 1700,
91+
'bt_xml_file': example_dir + '/behavior_trees_xml/move.xml'
92+
}
9393
])
9494

9595
transport_1_cmd = Node(
@@ -99,13 +99,13 @@ def generate_launch_description():
9999
namespace=namespace,
100100
output='screen',
101101
parameters=[
102-
example_dir + '/config/params.yaml',
103-
{
104-
'action_name': 'transport',
105-
'publisher_port': 1674,
106-
'server_port': 1675,
107-
'bt_xml_file': example_dir + '/behavior_trees_xml/transport.xml'
108-
}
102+
example_dir + '/config/params.yaml',
103+
{
104+
'action_name': 'transport',
105+
'enable_groot_monitoring': True,
106+
'server_port': 1700,
107+
'bt_xml_file': example_dir + '/behavior_trees_xml/transport.xml'
108+
}
109109
])
110110
transport_2_cmd = Node(
111111
package='plansys2_bt_actions',
@@ -114,13 +114,13 @@ def generate_launch_description():
114114
namespace=namespace,
115115
output='screen',
116116
parameters=[
117-
example_dir + '/config/params.yaml',
118-
{
119-
'action_name': 'transport',
120-
'publisher_port': 1676,
121-
'server_port': 1677,
122-
'bt_xml_file': example_dir + '/behavior_trees_xml/transport.xml'
123-
}
117+
example_dir + '/config/params.yaml',
118+
{
119+
'action_name': 'transport',
120+
'enable_groot_monitoring': True,
121+
'server_port': 1700,
122+
'bt_xml_file': example_dir + '/behavior_trees_xml/transport.xml'
123+
}
124124
])
125125
transport_3_cmd = Node(
126126
package='plansys2_bt_actions',
@@ -129,13 +129,13 @@ def generate_launch_description():
129129
namespace=namespace,
130130
output='screen',
131131
parameters=[
132-
example_dir + '/config/params.yaml',
133-
{
134-
'action_name': 'transport',
135-
'publisher_port': 1678,
136-
'server_port': 1679,
137-
'bt_xml_file': example_dir + '/behavior_trees_xml/transport.xml'
138-
}
132+
example_dir + '/config/params.yaml',
133+
{
134+
'action_name': 'transport',
135+
'enable_groot_monitoring': True,
136+
'server_port': 1700,
137+
'bt_xml_file': example_dir + '/behavior_trees_xml/transport.xml'
138+
}
139139
])
140140

141141
assemble_1_cmd = Node(
@@ -167,11 +167,11 @@ def generate_launch_description():
167167
namespace=namespace,
168168
output='screen',
169169
parameters=[
170-
example_dir + '/config/params.yaml',
171-
{
172-
'action_name': 'recharge',
173-
'bt_xml_file': example_dir + '/behavior_trees_xml/recharge.xml'
174-
}
170+
example_dir + '/config/params.yaml',
171+
{
172+
'action_name': 'recharge',
173+
'bt_xml_file': example_dir + '/behavior_trees_xml/recharge.xml'
174+
}
175175
])
176176

177177
ld = LaunchDescription()

plansys2_bt_example/src/assemble_action_node.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@ class AssembleAction : public plansys2::ActionExecutorClient
2626
{
2727
public:
2828
AssembleAction()
29-
: plansys2::ActionExecutorClient("assemble", 500ms)
29+
: plansys2::ActionExecutorClient("assemble")
3030
{
3131
progress_ = 0.0;
3232
}
@@ -58,6 +58,7 @@ int main(int argc, char ** argv)
5858
auto node = std::make_shared<AssembleAction>();
5959

6060
node->set_parameter(rclcpp::Parameter("action_name", "assemble"));
61+
node->set_parameter(rclcpp::Parameter("rate", 2.0));
6162
node->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE);
6263

6364
rclcpp::spin(node->get_node_base_interface());

plansys2_cascade_example/src/ask_charge_action_node.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@ class AskCharge : public plansys2::ActionExecutorClient
2626
{
2727
public:
2828
AskCharge()
29-
: plansys2::ActionExecutorClient("askcharge", 1s)
29+
: plansys2::ActionExecutorClient("askcharge")
3030
{
3131
progress_ = 0.0;
3232
}
@@ -58,6 +58,7 @@ int main(int argc, char ** argv)
5858
auto node = std::make_shared<AskCharge>();
5959

6060
node->set_parameter(rclcpp::Parameter("action_name", "askcharge"));
61+
node->set_parameter(rclcpp::Parameter("rate", 1.0));
6162
node->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE);
6263

6364
rclcpp::spin(node->get_node_base_interface());

plansys2_cascade_example/src/charge_action_node.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@ class ChargeAction : public plansys2::ActionExecutorClient
2626
{
2727
public:
2828
ChargeAction()
29-
: plansys2::ActionExecutorClient("charge", 500ms)
29+
: plansys2::ActionExecutorClient("charge")
3030
{
3131
progress_ = 0.0;
3232
}
@@ -58,6 +58,7 @@ int main(int argc, char ** argv)
5858
auto node = std::make_shared<ChargeAction>();
5959

6060
node->set_parameter(rclcpp::Parameter("action_name", "charge"));
61+
node->set_parameter(rclcpp::Parameter("rate", 2.0));
6162
node->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE);
6263

6364
rclcpp::spin(node->get_node_base_interface());

plansys2_cascade_example/src/move_action_node.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ class MoveAction : public plansys2::ActionExecutorClient
2929
{
3030
public:
3131
MoveAction()
32-
: plansys2::ActionExecutorClient("move", 250ms)
32+
: plansys2::ActionExecutorClient("move")
3333
{
3434
progress_ = 0.0;
3535

@@ -63,6 +63,7 @@ int main(int argc, char ** argv)
6363
auto node = std::make_shared<MoveAction>();
6464

6565
node->set_parameter(rclcpp::Parameter("action_name", "move"));
66+
node->set_parameter(rclcpp::Parameter("rate", 4.0));
6667
node->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE);
6768

6869
rclcpp::spin(node->get_node_base_interface());

plansys2_multidomain_example/src/ask_charge_action_node.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@ class AskCharge : public plansys2::ActionExecutorClient
2626
{
2727
public:
2828
AskCharge()
29-
: plansys2::ActionExecutorClient("askcharge", 1s)
29+
: plansys2::ActionExecutorClient("askcharge")
3030
{
3131
progress_ = 0.0;
3232
}
@@ -58,6 +58,7 @@ int main(int argc, char ** argv)
5858
auto node = std::make_shared<AskCharge>();
5959

6060
node->set_parameter(rclcpp::Parameter("action_name", "askcharge"));
61+
node->set_parameter(rclcpp::Parameter("rate", 1.0));
6162
node->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE);
6263

6364
rclcpp::spin(node->get_node_base_interface());

plansys2_multidomain_example/src/charge_action_node.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@ class ChargeAction : public plansys2::ActionExecutorClient
2626
{
2727
public:
2828
ChargeAction()
29-
: plansys2::ActionExecutorClient("charge", 500ms)
29+
: plansys2::ActionExecutorClient("charge")
3030
{
3131
progress_ = 0.0;
3232
}
@@ -58,6 +58,7 @@ int main(int argc, char ** argv)
5858
auto node = std::make_shared<ChargeAction>();
5959

6060
node->set_parameter(rclcpp::Parameter("action_name", "charge"));
61+
node->set_parameter(rclcpp::Parameter("rate", 2.0));
6162
node->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE);
6263

6364
rclcpp::spin(node->get_node_base_interface());

plansys2_multidomain_example/src/move_action_node.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@ class MoveAction : public plansys2::ActionExecutorClient
2626
{
2727
public:
2828
MoveAction()
29-
: plansys2::ActionExecutorClient("move", 250ms)
29+
: plansys2::ActionExecutorClient("move")
3030
{
3131
progress_ = 0.0;
3232
}
@@ -58,6 +58,7 @@ int main(int argc, char ** argv)
5858
auto node = std::make_shared<MoveAction>();
5959

6060
node->set_parameter(rclcpp::Parameter("action_name", "move"));
61+
node->set_parameter(rclcpp::Parameter("rate", 4.0));
6162
node->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE);
6263

6364
rclcpp::spin(node->get_node_base_interface());

plansys2_multidomain_example/src/pick_object_action_node.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@ class PickObject : public plansys2::ActionExecutorClient
2626
{
2727
public:
2828
PickObject()
29-
: plansys2::ActionExecutorClient("pick_object", 250ms)
29+
: plansys2::ActionExecutorClient("pick_object")
3030
{
3131
progress_ = 0.0;
3232
}
@@ -58,6 +58,7 @@ int main(int argc, char ** argv)
5858
auto node = std::make_shared<PickObject>();
5959

6060
node->set_parameter(rclcpp::Parameter("action_name", "pick_object"));
61+
node->set_parameter(rclcpp::Parameter("rate", 4.0));
6162
node->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE);
6263

6364
rclcpp::spin(node->get_node_base_interface());

plansys2_multidomain_example/src/place_object_action_node.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@ class PlaceObject : public plansys2::ActionExecutorClient
2626
{
2727
public:
2828
PlaceObject()
29-
: plansys2::ActionExecutorClient("place_object", 250ms)
29+
: plansys2::ActionExecutorClient("place_object")
3030
{
3131
progress_ = 0.0;
3232
}
@@ -58,6 +58,7 @@ int main(int argc, char ** argv)
5858
auto node = std::make_shared<PlaceObject>();
5959

6060
node->set_parameter(rclcpp::Parameter("action_name", "place_object"));
61+
node->set_parameter(rclcpp::Parameter("rate", 4.0));
6162
node->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE);
6263

6364
rclcpp::spin(node->get_node_base_interface());

0 commit comments

Comments
 (0)