32 #include <hector_uav_msgs/PoseAction.h> 33 #include <geometry_msgs/PoseStamped.h> 60 geometry_msgs::PoseStamped pose = goal->target_pose;
83 hector_uav_msgs::PoseFeedback feedback;
118 int main(
int argc,
char **argv)
void publish(const boost::shared_ptr< M > &message) const
double time_in_tolerance_
bool poseWithinTolerance(const geometry_msgs::Pose &pose_current, const geometry_msgs::Pose &pose_target, const double dist_tolerance, const double yaw_tolerance)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool enableMotors(bool enable)
int main(int argc, char **argv)
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()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void poseActionCb(const hector_uav_msgs::PoseGoalConstPtr &goal)
PoseActionServer(ros::NodeHandle nh)
hector_quadrotor_actions::BaseActionServer< hector_uav_msgs::PoseAction > pose_server_
ROSCPP_DECL void spinOnce()