31 #include <hector_uav_msgs/PoseAction.h> 32 #include <hector_uav_msgs/TakeoffAction.h> 62 hector_uav_msgs::PoseGoal pose_goal;
90 int main(
int argc,
char **argv)
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)
bool enableMotors(bool enable)
ROSCPP_DECL void spin(Spinner &spinner)
boost::shared_ptr< ActionServer > get()
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
geometry_msgs::PoseStampedConstPtr getPose()
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
TakeoffActionServer(ros::NodeHandle nh)
double connection_timeout_
void takeoffActionCb(const hector_uav_msgs::TakeoffGoalConstPtr &goal)
SimpleClientGoalState getState() const
#define ROS_ERROR_STREAM(args)