diff --git a/cfg/TiagoPlayMotionBtClient.cfg b/cfg/TiagoPlayMotionBtClient.cfg index 8f480c977966d487d2cabca61e36a55cde9dabd4..567e2b2ab9a6f5b022b2ccafdf2f7f71e1bae2bf 100755 --- a/cfg/TiagoPlayMotionBtClient.cfg +++ b/cfg/TiagoPlayMotionBtClient.cfg @@ -41,8 +41,6 @@ gen = ParameterGenerator() # Name Type Reconfiguration level Description Default Min Max #gen.add("velocity_scale_factor", double_t, 0, "Maximum velocity scale factor", 0.5, 0.0, 1.0) add_bt_client_params(gen) -gen.add("START", bool_t, 0, "synchronous start", False) -gen.add("RESTART", bool_t, 0, "asynchronous restart of BT", False) gen.add("motion_name", str_t, 0, "Motion name to execute", "") gen.add("set_motion", bool_t, 0, "Execute selected motion", False) # gen.add("cancel_motion", bool_t, 0, "Cancel current motion", False) diff --git a/src/tiago_play_motion_bt_client_alg_node.cpp b/src/tiago_play_motion_bt_client_alg_node.cpp index 6e9b5d1884a5b5c2b0a6591d2fe92c215be85b36..77d5ea57bbdb0c1b39afc67a3aa46fee3d5ec908 100644 --- a/src/tiago_play_motion_bt_client_alg_node.cpp +++ b/src/tiago_play_motion_bt_client_alg_node.cpp @@ -44,18 +44,6 @@ void TiagoPlayMotionModuleBtClientAlgNode::node_config_update(tiago_play_motion_ { this->lock(); - if(config.START) - { - this->core.start_tree(); - config.START=false; - } - - if(config.RESTART) - { - this->core.stop_tree(); - config.RESTART=false; - } - if (config.set_motion) { this->set_motion = true; diff --git a/src/xml/bt_definitions.xml b/src/xml/bt_definitions.xml index 08372101d6b11391c2ac2b93b2516763c39408c7..0028574ec769cc58ec5ff0f1f4436e1397fbdc64 100644 --- a/src/xml/bt_definitions.xml +++ b/src/xml/bt_definitions.xml @@ -2,20 +2,40 @@ <root main_tree_to_execute="BehaviorTree"> <!-- ////////// --> <BehaviorTree ID="BehaviorTree"> - <Action ID="NOP"/> + <Action ID="RUNNING"/> </BehaviorTree> <!-- ////////// --> <TreeNodesModel> <!-- basic_nodes --> - <Action ID="NOP"/> - <Action ID="is_not_start_tree"/> - <Condition ID="async_is_start_tree"/> - <Action ID="is_not_stop_tree"/> - <Condition ID="async_is_stop_tree"/> - <Action ID="set_start_tree"/> - <Action ID="set_stop_tree"/> - <Action ID="reset_start_tree"/> - <Action ID="reset_stop_tree"/> + <Action ID="RUNNING"/> + <Action ID="is_variable_true"> + <input_port name="variable"> (bool): Bool variable to check.</input_port> + </Action> + <Action ID="is_variable_false"> + <input_port name="variable"> (bool): Bool variable to check.</input_port> + </Action> + <Action ID="transform_pose"> + <input_port name="pose_in"> (geometry_msgs::PoseStamped): Pose to be transformed.</input_port> + <input_port name="target_frame"> (std::string): Frame to transform the pose.</input_port> + <output_port name="pose_out"> (geometry_msgs::PoseStamped): Transformed pose.</output_port> + </Action> + <Action ID="compute_distance"> + <input_port name="pose1"> (geometry_msgs::PoseStamped): Pose 1.</input_port> + <input_port name="pose2"> (geometry_msgs::PoseStamped): Pose 2.</input_port> + <output_port name="distance"> (double): Distance.</output_port> + </Action> + <Action ID="compare_bigger"> + <input_port name="value1"> (double): Value 1.</input_port> + <input_port name="value2"> (double): Value 2.</input_port> + </Action> + <Action ID="compare_smaller"> + <input_port name="value1"> (double): Value 1.</input_port> + <input_port name="value2"> (double): Value 2.</input_port> + </Action> + <Action ID="print_msg"> + <input_port name="msg"> (std::string): Msg to print.</input_port> + <input_port name="type"> (std::string): It must be info, warn, error or debug.</input_port> + </Action> <!-- tiago_play_motion_module --> <Action ID="sync_cancel_tiago_play_motion_action"/> <Action ID="async_cancel_tiago_play_motion_action"/> diff --git a/src/xml/bt_test.xml b/src/xml/bt_test.xml index 29804a4a04abac9ea7b34b5104a767d47606dfe7..f0a635a7b22d67a67213a13212475f23340c4442 100644 --- a/src/xml/bt_test.xml +++ b/src/xml/bt_test.xml @@ -3,7 +3,6 @@ <!-- ////////// --> <BehaviorTree ID="BehaviorTree"> <SequenceStar> - <Action ID="async_is_start_tree"/> <SubTree ID="execute_motion"/> </SequenceStar> </BehaviorTree> @@ -17,15 +16,35 @@ <!-- ////////// --> <TreeNodesModel> <!-- basic_nodes --> - <Action ID="NOP"/> - <Action ID="is_not_start_tree"/> - <Condition ID="async_is_start_tree"/> - <Action ID="is_not_stop_tree"/> - <Condition ID="async_is_stop_tree"/> - <Action ID="set_start_tree"/> - <Action ID="set_stop_tree"/> - <Action ID="reset_start_tree"/> - <Action ID="reset_stop_tree"/> + <Action ID="RUNNING"/> + <Action ID="is_variable_true"> + <input_port name="variable"> (bool): Bool variable to check.</input_port> + </Action> + <Action ID="is_variable_false"> + <input_port name="variable"> (bool): Bool variable to check.</input_port> + </Action> + <Action ID="transform_pose"> + <input_port name="pose_in"> (geometry_msgs::PoseStamped): Pose to be transformed.</input_port> + <input_port name="target_frame"> (std::string): Frame to transform the pose.</input_port> + <output_port name="pose_out"> (geometry_msgs::PoseStamped): Transformed pose.</output_port> + </Action> + <Action ID="compute_distance"> + <input_port name="pose1"> (geometry_msgs::PoseStamped): Pose 1.</input_port> + <input_port name="pose2"> (geometry_msgs::PoseStamped): Pose 2.</input_port> + <output_port name="distance"> (double): Distance.</output_port> + </Action> + <Action ID="compare_bigger"> + <input_port name="value1"> (double): Value 1.</input_port> + <input_port name="value2"> (double): Value 2.</input_port> + </Action> + <Action ID="compare_smaller"> + <input_port name="value1"> (double): Value 1.</input_port> + <input_port name="value2"> (double): Value 2.</input_port> + </Action> + <Action ID="print_msg"> + <input_port name="msg"> (std::string): Msg to print.</input_port> + <input_port name="type"> (std::string): It must be info, warn, error or debug.</input_port> + </Action> <!-- tiago_play_motion_module --> <Action ID="sync_cancel_tiago_play_motion_action"/> <Action ID="async_cancel_tiago_play_motion_action"/>