hovering_example.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland
3  * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland
4  * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland
5  * Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland
6  * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland
7  *
8  * Licensed under the Apache License, Version 2.0 (the "License");
9  * you may not use this file except in compliance with the License.
10  * You may obtain a copy of the License at
11  *
12  * http://www.apache.org/licenses/LICENSE-2.0
13 
14  * Unless required by applicable law or agreed to in writing, software
15  * distributed under the License is distributed on an "AS IS" BASIS,
16  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
17  * See the License for the specific language governing permissions and
18  * limitations under the License.
19  */
20 
21 #include <thread>
22 #include <chrono>
23 
24 #include <Eigen/Core>
25 #include <mav_msgs/conversions.h>
27 #include <ros/ros.h>
28 #include <std_srvs/Empty.h>
29 #include <trajectory_msgs/MultiDOFJointTrajectory.h>
30 
31 int main(int argc, char** argv) {
32  ros::init(argc, argv, "hovering_example");
34  // Create a private node handle for accessing node parameters.
35  ros::NodeHandle nh_private("~");
36  ros::Publisher trajectory_pub =
37  nh.advertise<trajectory_msgs::MultiDOFJointTrajectory>(
39  ROS_INFO("Started hovering example.");
40 
41  std_srvs::Empty srv;
42  bool unpaused = ros::service::call("/gazebo/unpause_physics", srv);
43  unsigned int i = 0;
44 
45  // Trying to unpause Gazebo for 10 seconds.
46  while (i <= 10 && !unpaused) {
47  ROS_INFO("Wait for 1 second before trying to unpause Gazebo again.");
48  std::this_thread::sleep_for(std::chrono::seconds(1));
49  unpaused = ros::service::call("/gazebo/unpause_physics", srv);
50  ++i;
51  }
52 
53  if (!unpaused) {
54  ROS_FATAL("Could not wake up Gazebo.");
55  return -1;
56  } else {
57  ROS_INFO("Unpaused the Gazebo simulation.");
58  }
59 
60  // Wait for 5 seconds to let the Gazebo GUI show up.
61  ros::Duration(5.0).sleep();
62 
63  trajectory_msgs::MultiDOFJointTrajectory trajectory_msg;
64  trajectory_msg.header.stamp = ros::Time::now();
65 
66  // Default desired position and yaw.
67  Eigen::Vector3d desired_position(0.0, 0.0, 1.0);
68  double desired_yaw = 0.0;
69 
70  // Overwrite defaults if set as node parameters.
71  nh_private.param("x", desired_position.x(), desired_position.x());
72  nh_private.param("y", desired_position.y(), desired_position.y());
73  nh_private.param("z", desired_position.z(), desired_position.z());
74  nh_private.param("yaw", desired_yaw, desired_yaw);
75 
77  desired_position, desired_yaw, &trajectory_msg);
78 
79  ROS_INFO("Publishing waypoint on namespace %s: [%f, %f, %f].",
80  nh.getNamespace().c_str(), desired_position.x(),
81  desired_position.y(), desired_position.z());
82  trajectory_pub.publish(trajectory_msg);
83 
84  ros::spinOnce();
85  ros::shutdown();
86 
87  return 0;
88 }
#define ROS_FATAL(...)
ros::NodeHandle nh
bool call(const std::string &service_name, MReq &req, MRes &res)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
#define ROS_INFO(...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
const std::string & getNamespace() const
static Time now()
void msgMultiDofJointTrajectoryFromPositionYaw(const Eigen::Vector3d &position, double yaw, trajectory_msgs::MultiDOFJointTrajectory *msg)
ROSCPP_DECL void shutdown()
bool sleep() const
static constexpr char COMMAND_TRAJECTORY[]
ROSCPP_DECL void spinOnce()


rotors_gazebo
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Mon Feb 28 2022 23:39:12