land.cpp
Go to the documentation of this file.
00001 /*
00002 Parker Conroy
00003 Algorithmic Robotics Lab @ University of Utah
00004 
00005 This program lands the ardrone. 
00006 It is intended as a simple example for those starting with the AR Drone platform.
00007 */
00008 
00009 #include <ros/ros.h>
00010 #include <std_msgs/Empty.h>
00011 
00012         std_msgs::Empty emp_msg;
00013         
00014 
00015 int main(int argc, char** argv)
00016 {
00017 
00018         ROS_INFO("Landing ARdrone");
00019         ros::init(argc, argv,"ARDrone_test");
00020     ros::NodeHandle node;
00021     ros::Rate loop_rate(50);
00022         ros::Publisher pub_empty;
00023 
00024         pub_empty = node.advertise<std_msgs::Empty>("/ardrone/land", 1); /* Message queue length is just 1 */
00025         
00026 
00027         while (ros::ok()) {
00028                          double time_start=(double)ros::Time::now().toSec();
00029                         while ((double)ros::Time::now().toSec()< time_start+5.0){
00030                 pub_empty.publish(emp_msg); //launches the droe
00031 
00032 
00033                         ros::spinOnce();
00034                         loop_rate.sleep();
00035 }
00036 ROS_INFO("ARdrone landed");
00037 exit(0);
00038                         }//ros::ok
00039 
00040 }//main


arl_ardrone_examples
Author(s): parcon
autogenerated on Mon Jan 6 2014 11:03:12