28 #include <std_srvs/Empty.h> 29 #include <trajectory_msgs/MultiDOFJointTrajectory.h> 31 int main(
int argc,
char** argv) {
32 ros::init(argc, argv,
"hovering_example");
37 nh.
advertise<trajectory_msgs::MultiDOFJointTrajectory>(
39 ROS_INFO(
"Started hovering example.");
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));
57 ROS_INFO(
"Unpaused the Gazebo simulation.");
63 trajectory_msgs::MultiDOFJointTrajectory trajectory_msg;
67 Eigen::Vector3d desired_position(0.0, 0.0, 1.0);
68 double desired_yaw = 0.0;
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);
77 desired_position, desired_yaw, &trajectory_msg);
79 ROS_INFO(
"Publishing waypoint on namespace %s: [%f, %f, %f].",
81 desired_position.y(), desired_position.z());
82 trajectory_pub.
publish(trajectory_msg);
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 ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
const std::string & getNamespace() const
void msgMultiDofJointTrajectoryFromPositionYaw(const Eigen::Vector3d &position, double yaw, trajectory_msgs::MultiDOFJointTrajectory *msg)
ROSCPP_DECL void shutdown()
static constexpr char COMMAND_TRAJECTORY[]
ROSCPP_DECL void spinOnce()