hovering_example.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland
00003  * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland
00004  * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland
00005  * Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland
00006  * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland
00007  *
00008  * Licensed under the Apache License, Version 2.0 (the "License");
00009  * you may not use this file except in compliance with the License.
00010  * You may obtain a copy of the License at
00011  *
00012  *     http://www.apache.org/licenses/LICENSE-2.0
00013 
00014  * Unless required by applicable law or agreed to in writing, software
00015  * distributed under the License is distributed on an "AS IS" BASIS,
00016  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00017  * See the License for the specific language governing permissions and
00018  * limitations under the License.
00019  */
00020 
00021 #include <thread>
00022 #include <chrono>
00023 
00024 #include <Eigen/Core>
00025 #include <mav_msgs/conversions.h>
00026 #include <mav_msgs/default_topics.h>
00027 #include <ros/ros.h>
00028 #include <std_srvs/Empty.h>
00029 #include <trajectory_msgs/MultiDOFJointTrajectory.h>
00030 
00031 int main(int argc, char** argv) {
00032   ros::init(argc, argv, "hovering_example");
00033   ros::NodeHandle nh;
00034   // Create a private node handle for accessing node parameters.
00035   ros::NodeHandle nh_private("~");
00036   ros::Publisher trajectory_pub =
00037       nh.advertise<trajectory_msgs::MultiDOFJointTrajectory>(
00038           mav_msgs::default_topics::COMMAND_TRAJECTORY, 10);
00039   ROS_INFO("Started hovering example.");
00040 
00041   std_srvs::Empty srv;
00042   bool unpaused = ros::service::call("/gazebo/unpause_physics", srv);
00043   unsigned int i = 0;
00044 
00045   // Trying to unpause Gazebo for 10 seconds.
00046   while (i <= 10 && !unpaused) {
00047     ROS_INFO("Wait for 1 second before trying to unpause Gazebo again.");
00048     std::this_thread::sleep_for(std::chrono::seconds(1));
00049     unpaused = ros::service::call("/gazebo/unpause_physics", srv);
00050     ++i;
00051   }
00052 
00053   if (!unpaused) {
00054     ROS_FATAL("Could not wake up Gazebo.");
00055     return -1;
00056   } else {
00057     ROS_INFO("Unpaused the Gazebo simulation.");
00058   }
00059 
00060   // Wait for 5 seconds to let the Gazebo GUI show up.
00061   ros::Duration(5.0).sleep();
00062 
00063   trajectory_msgs::MultiDOFJointTrajectory trajectory_msg;
00064   trajectory_msg.header.stamp = ros::Time::now();
00065 
00066   // Default desired position and yaw.
00067   Eigen::Vector3d desired_position(0.0, 0.0, 1.0);
00068   double desired_yaw = 0.0;
00069 
00070   // Overwrite defaults if set as node parameters.
00071   nh_private.param("x", desired_position.x(), desired_position.x());
00072   nh_private.param("y", desired_position.y(), desired_position.y());
00073   nh_private.param("z", desired_position.z(), desired_position.z());
00074   nh_private.param("yaw", desired_yaw, desired_yaw);
00075 
00076   mav_msgs::msgMultiDofJointTrajectoryFromPositionYaw(
00077       desired_position, desired_yaw, &trajectory_msg);
00078 
00079   ROS_INFO("Publishing waypoint on namespace %s: [%f, %f, %f].",
00080            nh.getNamespace().c_str(), desired_position.x(),
00081            desired_position.y(), desired_position.z());
00082   trajectory_pub.publish(trajectory_msg);
00083 
00084   ros::spinOnce();
00085   ros::shutdown();
00086 
00087   return 0;
00088 }


rotors_gazebo
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Thu Apr 18 2019 02:43:49