Skip to content
Snippets Groups Projects
Commit 934e7867 authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Removed the async actions and conditions.

Used the module name space as a prefix for the actions and conditions names.
parent 1df826b6
No related branches found
No related tags found
No related merge requests found
......@@ -65,35 +65,7 @@ class CTiagoHeadModuleBT
* If inputs are missing or incorrect it also returns BT:NodeStatus::FAILURE.
*
*/
BT::NodeStatus sync_tiago_head_point_to_pointstamped(BT::TreeNode& self);
/**
* \brief Async point_to TIAGo head function.
*
* This function calls point_to of tiago_head_module. As this is
* an asynchronous action is_tiago_head_finished() is checked to know when the action
* has actually finished.
*
* It has the following input ports:
*
* point (geometry_msgs::PointStamped): The target Point.
*
* duration (double): [Optional] Time from start to move the head.
*
* It also has a bidirectional port:
*
* new_goal (bool): If it's a new_goal.
*
* \param self node with the required inputs defined as follows:
*
* \return a BT:NodeStatus indicating whether the request has been
* successfull and the action has finished (BT:NodeStatus::SUCCESS) or the
* request has been unsuccessfull (BT:NodeStatus::FAILURE) or it is still
* in progress (BT:NodeStatus::RUNNING). If inputs are missing or incorrect
* it also returns BT:NodeStatus::FAILURE
*
*/
BT::NodeStatus async_tiago_head_point_to_pointstamped(BT::TreeNode& self);
BT::NodeStatus tiago_head_point_to_pointstamped(BT::TreeNode& self);
/**
* \brief Synchronized point_to TIAGo head function.
......@@ -123,43 +95,7 @@ class CTiagoHeadModuleBT
* If inputs are missing or incorrect it also returns BT:NodeStatus::FAILURE.
*
*/
BT::NodeStatus sync_tiago_head_point_to(BT::TreeNode& self);
/**
* \brief Async point_to TIAGo head function.
*
* This function calls point_to of tiago_head_module. As this is
* an asynchronous action is_tiago_head_finished() is checked to know when the action
* has actually finished.
*
* It has the following input ports:
*
* x (double): The target Point x coordenate.
*
* y (double): The target Point y coordenate.
*
* z (double): The target Point z coordenate.
*
* frame_id (std::string): The target Point reference frame id.
*
* time (ros:Time): Time at which the desired coordinate was defined
*
* duration (double): [Optional] Time from start to move the head.
*
* It also has a bidirectional port:
*
* new_goal (bool): If it's a new_goal.
*
* \param self node with the required inputs defined as follows:
*
* \return a BT:NodeStatus indicating whether the request has been
* successfull and the action has finished (BT:NodeStatus::SUCCESS) or the
* request has been unsuccessfull (BT:NodeStatus::FAILURE) or it is still
* in progress (BT:NodeStatus::RUNNING). If inputs are missing or incorrect
* it also returns BT:NodeStatus::FAILURE
*
*/
BT::NodeStatus async_tiago_head_point_to(BT::TreeNode& self);
BT::NodeStatus tiago_head_point_to(BT::TreeNode& self);
/**
* \brief Synchronized move_to TIAGo head function.
......@@ -183,37 +119,7 @@ class CTiagoHeadModuleBT
* If inputs are missing or incorrect it also returns BT:NodeStatus::FAILURE.
*
*/
BT::NodeStatus sync_tiago_head_move_to(BT::TreeNode& self);
/**
* \brief Async move_to TIAGo head function.
*
* This function calls move_to of tiago_head_module. As this is
* an asynchronous action is_tiago_head_finished() is checked to know when the action
* has actually finished.
*
* It has the following input ports:
*
* pan (double): Desired angle for the pan joint in radians.
*
* tilt (double): Desired angle for the tilt joint in radians.
*
* duration (double): [Optional] Time from start to move the head.
*
* It also has a bidirectional port:
*
* new_goal (bool): If it's a new_goal.
*
* \param self node with the required inputs defined as follows:
*
* \return a BT:NodeStatus indicating whether the request has been
* successfull and the action has finished (BT:NodeStatus::SUCCESS) or the
* request has been unsuccessfull (BT:NodeStatus::FAILURE) or it is still
* in progress (BT:NodeStatus::RUNNING). If inputs are missing or incorrect
* it also returns BT:NodeStatus::FAILURE
*
*/
BT::NodeStatus async_tiago_head_move_to(BT::TreeNode& self);
BT::NodeStatus tiago_head_move_to(BT::TreeNode& self);
/**
* \brief Synchronized move_to TIAGo head function.
......@@ -237,37 +143,7 @@ class CTiagoHeadModuleBT
* If inputs are missing or incorrect it also returns BT:NodeStatus::FAILURE.
*
*/
BT::NodeStatus sync_tiago_head_move_to_trajectory(BT::TreeNode& self);
/**
* \brief Async move_to TIAGo head function.
*
* This function calls move_to of tiago_head_module. As this is
* an asynchronous action is_tiago_head_finished() is checked to know when the action
* has actually finished.
*
* It has the following input ports:
*
* pan (std::vector<double>): Desired angles for the pan joint in radians.
*
* tilt (std::vector<double>): Desired angles for the tilt joint in radians.
*
* duration (std::vector<double>): Times from start to move the head.
*
* It also has a bidirectional port:
*
* new_goal (bool): If it's a new_goal.
*
* \param self node with the required inputs defined as follows:
*
* \return a BT:NodeStatus indicating whether the request has been
* successfull and the action has finished (BT:NodeStatus::SUCCESS) or the
* request has been unsuccessfull (BT:NodeStatus::FAILURE) or it is still
* in progress (BT:NodeStatus::RUNNING). If inputs are missing or incorrect
* it also returns BT:NodeStatus::FAILURE
*
*/
BT::NodeStatus async_tiago_head_move_to_trajectory(BT::TreeNode& self);
BT::NodeStatus tiago_head_move_to_trajectory(BT::TreeNode& self);
/**
* \brief Synchronized move_to_by_topic TIAGo head function.
......@@ -289,7 +165,7 @@ class CTiagoHeadModuleBT
* If inputs are missing or incorrect it also returns BT:NodeStatus::FAILURE.
*
*/
BT::NodeStatus sync_tiago_head_move_to_by_topic(BT::TreeNode& self);
BT::NodeStatus tiago_head_move_to_by_topic(BT::TreeNode& self);
/**
* \brief Synchronized move_relative_angles_by_topic TIAGo head function.
......@@ -311,7 +187,7 @@ class CTiagoHeadModuleBT
* If inputs are missing or incorrect it also returns BT:NodeStatus::FAILURE.
*
*/
BT::NodeStatus sync_tiago_head_move_relative_angles_by_topic(BT::TreeNode& self);
BT::NodeStatus tiago_head_move_relative_angles_by_topic(BT::TreeNode& self);
/**
* \brief Synchronized set_workspace TIAGo head function.
......@@ -361,23 +237,7 @@ class CTiagoHeadModuleBT
* If inputs are missing or incorrect it also returns BT:NodeStatus::FAILURE.
*
*/
BT::NodeStatus sync_cancel_tiago_head_action(void);
/**
* \brief Async stop TIAGo head function.
*
* This function calls stop of tiago_head_module. As this is
* an asynchronous action is_tiago_head_finished() is checked to know when the action
* has actually finished.
*
* \return a BT:NodeStatus indicating whether the request has been
* successfull and the action has finished (BT:NodeStatus::SUCCESS) or the
* request has been unsuccessfull (BT:NodeStatus::FAILURE) or it is still
* in progress (BT:NodeStatus::RUNNING). If inputs are missing or incorrect
* it also returns BT:NodeStatus::FAILURE
*
*/
BT::NodeStatus async_cancel_tiago_head_action(void);
BT::NodeStatus cancel_tiago_head_action(void);
/**
* \brief Checks if the module is idle and there isn't any new movement request.
......@@ -391,19 +251,6 @@ class CTiagoHeadModuleBT
*/
BT::NodeStatus is_tiago_head_finished(void);
/**
* \brief Checks if the module is idle and there isn't any new movement request.
*
* This function must be used when any sync action is called and
* a BT timeout is used.
*
* \return a BT:NodeStatus indicating whether the last movement has
* ended (BT:NodeStatus::SUCCESS) or not (BT:NodeStatus::RUNNING),
* regardless of its success or not.
*
*/
BT::NodeStatus async_is_tiago_head_finished(void);
///TIAGo head module status
/**
* \brief Checks if the module is active and operating properly.
......
This diff is collapsed.
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment