base_action.h
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2012-2016, Institute of Flight Systems and Automatic Control,
3 // Technische Universität Darmstadt.
4 // All rights reserved.
5 
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of hector_quadrotor nor the names of its contributors
14 // may be used to endorse or promote products derived from this software
15 // without specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 #ifndef HECTOR_QUADROTOR_ACTIONS_BASE_ACTION_H
30 #define HECTOR_QUADROTOR_ACTIONS_BASE_ACTION_H
31 
32 #include <ros/ros.h>
35 #include "geometry_msgs/PoseStamped.h"
36 #include <hector_uav_msgs/EnableMotors.h>
37 
39 {
40 
41 template <class ActionSpec>
43 {
44 public:
45 
47 
48  BaseActionServer(ros::NodeHandle nh, std::string server_name, typename ActionServer::ExecuteCallback callback)
49  : pose_sub_(nh, "pose"),
50  as_(boost::make_shared<ActionServer>(nh, server_name, callback, false))
51  {
52  nh.param<double>("connection_timeout", connection_timeout_, 10.0);
53 
54  server_name_ = nh.resolveName(server_name);
55 
56  motor_enable_service_ = nh.serviceClient<hector_uav_msgs::EnableMotors>("enable_motors");
58  ROS_ERROR_STREAM("Could not connect to " << nh.resolveName("enable_motors"));
59  }
60 
61  start_timer_ = nh.createTimer(ros::Duration(0.1), boost::bind(&BaseActionServer::startCb, this));
62  }
63 
64  /*
65  * Guaranteed to be available after server has started
66  */
67  geometry_msgs::PoseStampedConstPtr getPose()
68  {
69  return pose_sub_.get();
70  }
71 
73 
74  bool enableMotors(bool enable)
75  {
76  hector_uav_msgs::EnableMotors srv;
77  srv.request.enable = enable;
78  return motor_enable_service_.call(srv);
79  }
80 
81 private:
82 
83  void startCb()
84  {
85  if (!pose_sub_.get())
86  {
87  ROS_INFO_STREAM_THROTTLE(1.0, "Waiting for position state to be available before starting " << server_name_ <<
88  " server");
89  }
90  else
91  {
92  as_->start();
93  ROS_INFO_STREAM("Server " << server_name_ << " started");
95  }
96  }
97 
99 
100  std::string server_name_;
104 
106 
107 };
108 
109 }
110 
111 #endif //HECTOR_QUADROTOR_ACTIONS_BASE_ACTION_H
hector_quadrotor_interface::PoseSubscriberHelper pose_sub_
Definition: base_action.h:102
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
std::string resolveName(const std::string &name, bool remap=true) const
void stop()
bool call(MReq &req, MRes &res)
geometry_msgs::PoseStampedConstPtr get() const
boost::function< void(const GoalConstPtr &)> ExecuteCallback
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
bool param(const std::string &param_name, T &param_val, const T &default_val) const
actionlib::SimpleActionServer< ActionSpec > ActionServer
Definition: base_action.h:46
geometry_msgs::PoseStampedConstPtr getPose()
Definition: base_action.h:67
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
BaseActionServer(ros::NodeHandle nh, std::string server_name, typename ActionServer::ExecuteCallback callback)
Definition: base_action.h:48
#define ROS_INFO_STREAM(args)
#define ROS_ERROR_STREAM(args)
#define ROS_INFO_STREAM_THROTTLE(rate, args)
boost::shared_ptr< ActionServer > as_
Definition: base_action.h:98


hector_quadrotor_actions
Author(s): Paul Bovbel
autogenerated on Mon Jun 10 2019 13:36:49