toolsForAction.hpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 SoftBank Robotics Europe
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015 */
00016 
00017 #ifndef TOOLSFORACTION_HPP
00018 #define TOOLSFORACTION_HPP
00019 
00020 // ROS
00021 #include <ros/ros.h>
00022 
00023 namespace moveit_simple_actions
00024 {
00025 
00027 template<typename T>
00028 void waitForAction(const T &action,
00029                    const ros::NodeHandle &node_handle,
00030                    const ros::Duration &wait_for_server,
00031                    const std::string &name)
00032 {
00033   ROS_DEBUG("Waiting for MoveGroup action server (%s)...", name.c_str());
00034 
00035   // in case ROS time is published, wait for the time data to arrive
00036   ros::Time start_time = ros::Time::now();
00037   while (start_time == ros::Time::now())
00038   {
00039     ros::WallDuration(0.01).sleep();
00040     ros::spinOnce();
00041   }
00042 
00043   // wait for the server (and spin as needed)
00044   if (wait_for_server == ros::Duration(0, 0))
00045   {
00046     while (node_handle.ok() && !action->isServerConnected())
00047     {
00048       ros::WallDuration(0.02).sleep();
00049       ros::spinOnce();
00050     }
00051   }
00052   else
00053   {
00054     ros::Time final_time = ros::Time::now() + wait_for_server;
00055     while (node_handle.ok() && !action->isServerConnected()
00056            && final_time > ros::Time::now())
00057     {
00058       ros::WallDuration(0.02).sleep();
00059       ros::spinOnce();
00060     }
00061   }
00062 
00063   if (!action->isServerConnected())
00064     throw std::runtime_error("Unable to connect to the action server within allotted time (2)");
00065   else
00066     ROS_DEBUG("Connected to '%s'", name.c_str());
00067 }
00068 }
00069 
00070 #endif // TOOLSFORACTION_HPP


romeo_moveit_actions
Author(s):
autogenerated on Thu Jun 6 2019 21:57:24