ros_condition.cpp
Go to the documentation of this file.
00001 /* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved
00002 *
00003 *   Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"),
00004 *   to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense,
00005 *   and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:
00006 *   The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
00007 *
00008 *   THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
00009 *   FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
00010 *   WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
00011 */
00012 
00013 
00014 #include <conditions/ros_condition.h>
00015 #include <string>
00016 
00017 enum Status {RUNNING, SUCCESS, FAILURE};
00018 
00019 
00020 BT::ROSCondition::ROSCondition(std::string name) :
00021   ConditionNode::ConditionNode(name),
00022   action_client_(name, true)
00023 {
00024     ROS_INFO("Waiting For the Acutator named %s to start", get_name().c_str());
00025     action_client_.waitForServer();  // will wait for infinite time until the server starts
00026     ROS_INFO("Actuator %s Started", get_name().c_str());
00027 }
00028 
00029 BT::ROSCondition::~ROSCondition() {}
00030 
00031 BT::ReturnStatus BT::ROSCondition::Tick()
00032 {
00033     ROS_INFO("I am running the request");
00034 
00035     // Condition checking and state update
00036     action_client_.sendGoal(goal);
00037     action_client_.waitForResult(ros::Duration(30.0));
00038     node_result = *(action_client_.getResult());
00039     set_status((ReturnStatus)node_result.status);
00040     return (ReturnStatus)node_result.status;
00041 }


behavior_tree_core
Author(s): Michele Colledanchise
autogenerated on Thu Jun 6 2019 18:19:08