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


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