takeoff_action.cpp
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 #include <ros/ros.h>
31 #include <hector_uav_msgs/PoseAction.h>
32 #include <hector_uav_msgs/TakeoffAction.h>
35 
37 {
38 
40 {
41 public:
43  : takeoff_server_(nh, "action/takeoff", boost::bind(&TakeoffActionServer::takeoffActionCb, this, _1)),
44  pose_client_(nh, "action/pose")
45  {
46  nh.param<double>("action_frequency", frequency_, 10.0);
47  nh.param<double>("takeoff_height", takeoff_height_, 0.3);
48  nh.param<double>("connection_timeout", connection_timeout_, 10.0);
49  nh.param<double>("action_timout", action_timeout_, 30.0);
50 
51  if(!pose_client_.waitForServer(ros::Duration(connection_timeout_))){
52  ROS_ERROR_STREAM("Could not connect to " << nh.resolveName("action/pose"));
53  }
54  }
55 
56  void takeoffActionCb(const hector_uav_msgs::TakeoffGoalConstPtr &goal)
57  {
58 
60  {
61 
62  hector_uav_msgs::PoseGoal pose_goal;
63  pose_goal.target_pose = *takeoff_server_.getPose();
64  pose_goal.target_pose.pose.position.z = takeoff_height_;
65  pose_client_.sendGoal(pose_goal);
67 
69  {
70  ROS_WARN("Takeoff succeeded");
71  takeoff_server_.get()->setSucceeded();
72  return;
73  }
74  }
75  ROS_WARN("Takeoff failed");
76  takeoff_server_.get()->setAborted();
77  }
78 
79 private:
83 
85 };
86 
87 } // namespace hector_quadrotor_actions
88 
89 
90 int main(int argc, char **argv)
91 {
92  ros::init(argc, argv, "takeoff_action");
93 
94  ros::NodeHandle nh;
96 
97  ros::spin();
98 
99  return 0;
100 }
int main(int argc, char **argv)
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
actionlib::SimpleActionClient< hector_uav_msgs::PoseAction > pose_client_
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
std::string resolveName(const std::string &name, bool remap=true) const
hector_quadrotor_actions::BaseActionServer< hector_uav_msgs::TakeoffAction > takeoff_server_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_WARN(...)
ROSCPP_DECL void spin(Spinner &spinner)
boost::shared_ptr< ActionServer > get()
Definition: base_action.h:72
bool param(const std::string &param_name, T &param_val, const T &default_val) const
geometry_msgs::PoseStampedConstPtr getPose()
Definition: base_action.h:67
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
void takeoffActionCb(const hector_uav_msgs::TakeoffGoalConstPtr &goal)
SimpleClientGoalState getState() const
#define ROS_ERROR_STREAM(args)


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