run_motion_node.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (Modified BSD License)
00003  *
00004  *  Copyright (c) 2016, PAL Robotics, S.L.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of PAL Robotics, S.L. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00038 // C++ standard headers
00039 #include <exception>
00040 #include <string>
00041 
00042 // Boost headers
00043 #include <boost/shared_ptr.hpp>
00044 
00045 // ROS headers
00046 #include <ros/ros.h>
00047 #include <actionlib/client/simple_action_client.h>
00048 #include <play_motion_msgs/PlayMotionAction.h>
00049 
00050 // C++ standard headers
00051 #include <cstdlib>
00052 
00053 
00054 int main(int argc, char** argv)
00055 {
00056   // Init the ROS node
00057   ros::init(argc, argv, "run_motion");
00058 
00059   if ( argc < 2 )
00060   {
00061       ROS_INFO(" ");
00062       ROS_INFO("Usage:");
00063       ROS_INFO(" ");
00064       ROS_INFO("\trosrun run_motion run_motion MOTION_NAME");
00065       ROS_INFO(" ");
00066       ROS_INFO("\twhere MOTION_NAME must be one of the motions listed in: ");
00067       ROS_INFO_STREAM(std::system("rosparam list /play_motion/motions | grep joints | cut -d'/' -f4"));
00068       ROS_INFO(" ");
00069       return EXIT_FAILURE;
00070   }
00071 
00072   ROS_INFO("Starting run_motion application ...");
00073 
00074   // Precondition: Valid clock
00075   ros::NodeHandle nh;
00076   if (!ros::Time::waitForValid(ros::WallDuration(10.0))) // NOTE: Important when using simulated clock
00077   {
00078     ROS_FATAL("Timed-out waiting for valid time.");
00079     return EXIT_FAILURE;
00080   }
00081 
00082   actionlib::SimpleActionClient<play_motion_msgs::PlayMotionAction> client("/play_motion", true);
00083 
00084   ROS_INFO("Waiting for Action Server ...");
00085   client.waitForServer();
00086 
00087   play_motion_msgs::PlayMotionGoal goal;
00088 
00089   goal.motion_name = argv[1];
00090   goal.skip_planning = false;
00091   goal.priority = 0;
00092 
00093   ROS_INFO_STREAM("Sending goal with motion: " << argv[1]);
00094   client.sendGoal(goal);
00095 
00096   ROS_INFO("Waiting for result ...");
00097   bool actionOk = client.waitForResult(ros::Duration(30.0));
00098 
00099   actionlib::SimpleClientGoalState state = client.getState();
00100 
00101   if ( actionOk )
00102   {
00103       ROS_INFO_STREAM("Action finished successfully with state: " << state.toString());
00104   }
00105   else
00106   {
00107       ROS_ERROR_STREAM("Action failed with state: " << state.toString());
00108   }
00109 
00110   return EXIT_SUCCESS;
00111 }


play_motion
Author(s): Paul Mathieu , Adolfo Rodriguez Tsouroukdissian
autogenerated on Sat Jun 8 2019 20:26:22