Skip to content

Commit

Permalink
[fix] MGI server timeout, infinite duration by default (#349)
Browse files Browse the repository at this point in the history
By setting the default server timeout duration to -1, the MoveGroupInterface is ensured to be ready to use after construction.
  • Loading branch information
bostoncleek committed Jan 29, 2021
1 parent d41811b commit e108c35
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -148,22 +148,22 @@ class MoveGroupInterface
(which is the default type of callback queues used in ROS)
\param tf_buffer. Specify a TF2_ROS Buffer instance to use. If not specified,
one will be constructed internally along with an internal TF2_ROS TransformListener
\param wait_for_servers. Timeout for connecting to action servers. Zero time means unlimited waiting.
\param wait_for_servers. Timeout for connecting to action servers. -1 time means unlimited waiting.
*/
MoveGroupInterface(const rclcpp::Node::SharedPtr& node, const Options& opt,
const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>(),
const rclcpp::Duration& wait_for_servers = rclcpp::Duration(0.0));
const rclcpp::Duration& wait_for_servers = rclcpp::Duration(-1));

/**
\brief Construct a client for the MoveGroup action for a particular \e group.
\param tf_buffer. Specify a TF2_ROS Buffer instance to use. If not specified,
one will be constructed internally along with an internal TF2_ROS TransformListener
\param wait_for_servers. Timeout for connecting to action servers. Zero time means unlimited waiting.
\param wait_for_servers. Timeout for connecting to action servers. -1 time means unlimited waiting.
*/
MoveGroupInterface(const rclcpp::Node::SharedPtr& node, const std::string& group,
const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>(),
const rclcpp::Duration& wait_for_servers = rclcpp::Duration(0.0));
const rclcpp::Duration& wait_for_servers = rclcpp::Duration(-1));

~MoveGroupInterface();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -143,12 +143,8 @@ class MoveGroupInterface::MoveGroupInterfaceImpl

current_state_monitor_ = getSharedStateMonitor(node_, robot_model_, tf_buffer_);

rclcpp::Time timeout_for_servers = pnode_->now() + wait_for_servers;
if (wait_for_servers == rclcpp::Duration(0.0))
timeout_for_servers = rclcpp::Time(); // wait for ever

move_action_client_ = rclcpp_action::create_client<moveit_msgs::action::MoveGroup>(pnode_, move_group::MOVE_ACTION);
move_action_client_->wait_for_action_server(std::chrono::nanoseconds(timeout_for_servers.nanoseconds()));
move_action_client_->wait_for_action_server(wait_for_servers.to_chrono<std::chrono::duration<double>>());
// TODO(JafarAbdi): Enable once moveit_ros_manipulation is ported
// pick_action_client_ = rclcpp_action::create_client<moveit_msgs::action::Pickup>(
// node_, move_group::PICKUP_ACTION);
Expand All @@ -159,7 +155,7 @@ class MoveGroupInterface::MoveGroupInterfaceImpl
// place_action_client_->wait_for_action_server(std::chrono::nanoseconds(timeout_for_servers.nanoseconds()));
execute_action_client_ =
rclcpp_action::create_client<moveit_msgs::action::ExecuteTrajectory>(pnode_, move_group::EXECUTE_ACTION_NAME);
execute_action_client_->wait_for_action_server(std::chrono::nanoseconds(timeout_for_servers.nanoseconds()));
execute_action_client_->wait_for_action_server(wait_for_servers.to_chrono<std::chrono::duration<double>>());

query_service_ =
pnode_->create_client<moveit_msgs::srv::QueryPlannerInterfaces>(move_group::QUERY_PLANNERS_SERVICE_NAME);
Expand Down

0 comments on commit e108c35

Please sign in to comment.