Skip to content

Commit

Permalink
warehouse: added params for timeout + #retries (#1008)
Browse files Browse the repository at this point in the history
  • Loading branch information
dg-shadow authored and rhaschke committed Aug 20, 2018
1 parent 2d27391 commit b79cd2f
Showing 1 changed file with 17 additions and 4 deletions.
21 changes: 17 additions & 4 deletions moveit_ros/warehouse/warehouse/src/warehouse_services.cpp
Expand Up @@ -130,21 +130,34 @@ int main(int argc, char** argv)

ros::NodeHandle node;
std::string host;

int port;
float connection_timeout;
int connection_retries;

node.param<std::string>("warehouse_host", host, "localhost");
node.param<int>("warehouse_port", port, 33829);
node.param<float>("warehouse_db_connection_timeout", connection_timeout, 5.0);
node.param<int>("warehouse_db_connection_retries", connection_retries, 5);

warehouse_ros::DatabaseConnection::Ptr conn;

try
{
conn = moveit_warehouse::loadDatabase();
conn->setParams(host, port, 5.0);
conn->setParams(host, port, connection_timeout);

ROS_INFO("Connecting to warehouse on %s:%d", host.c_str(), port);
if (!conn->connect())
int tries = 0;
while (!conn->connect())
{
ROS_ERROR("Failed to connect to DB on %s:%d", host.c_str(), port);
return 1;
++tries;
ROS_WARN("Failed to connect to DB on %s:%d (try %d/%d).", host.c_str(), port, tries, connection_retries);
if (tries == connection_retries)
{
ROS_FATAL("Failed to connect too many times, giving up");
return 1;
}
}
}
catch (std::exception& ex)
Expand Down

0 comments on commit b79cd2f

Please sign in to comment.