Skip to content

Commit

Permalink
[Python wrapper] Added custom time limit for wait_for_servers in Move…
Browse files Browse the repository at this point in the history
…GroupInterface (moveit#1444)

* Added custom time limit for wait_for_servers

* Retained current hardcoded 5 second limit
* Used double to conform to python accessible API instead of `ros::WallDuration(int, int)`
* API is extended, remains conformant to previous releases

* Ran clang-format on a webedit
  • Loading branch information
kunaltyagi authored and v4hn committed Mar 31, 2020
1 parent 938cf93 commit 224c5b5
Showing 1 changed file with 2 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -67,10 +67,10 @@ class MoveGroupInterfaceWrapper : protected py_bindings_tools::ROScppInitializer
// ROSInitializer is constructed first, and ensures ros::init() was called, if
// needed
MoveGroupInterfaceWrapper(const std::string& group_name, const std::string& robot_description,
const std::string& ns = "")
const std::string& ns = "", double wait_for_servers = 5.0)
: py_bindings_tools::ROScppInitializer()
, MoveGroupInterface(Options(group_name, robot_description, ros::NodeHandle(ns)),
std::shared_ptr<tf2_ros::Buffer>(), ros::WallDuration(5, 0))
std::shared_ptr<tf2_ros::Buffer>(), ros::WallDuration(wait_for_servers))
{
}

Expand Down

0 comments on commit 224c5b5

Please sign in to comment.