00001 /* 00002 * Copyright (c) 2010, Robot Control and Pattern Recognition Group, Warsaw University of Technology. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Robot Control and Pattern Recognition Group, 00014 * Warsaw University of Technology nor the names of its contributors may 00015 * be used to endorse or promote products derived from this software 00016 * without specific prior written permission. 00017 * 00018 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00019 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00020 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00021 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00022 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00023 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00024 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00025 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00026 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00027 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00028 * POSSIBILITY OF SUCH DAMAGE. 00029 */ 00030 00031 /* 00032 * JointTrajectoryAction.h 00033 * 00034 * Created on: 23-09-2010 00035 * Author: Konrad Banachowicz 00036 */ 00037 00038 #ifndef JOINTTRAJECTORYACTION_H_ 00039 #define JOINTTRAJECTORYACTION_H_ 00040 00041 #include <string> 00042 #include <vector> 00043 00044 //#include <boost/shared_ptr.h> 00045 00046 #include <rtt/TaskContext.hpp> 00047 #include <rtt/Port.hpp> 00048 #include <rtt/Property.hpp> 00049 00050 #include <oro_action_server.h> 00051 00052 #include <control_msgs/FollowJointTrajectoryAction.h> 00053 #include <control_msgs/FollowJointTrajectoryActionGoal.h> 00054 00055 #include <trajectory_msgs/JointTrajectoryPoint.h> 00056 #include <trajectory_msgs/JointTrajectory.h> 00057 00058 class JointTrajectoryAction : public RTT::TaskContext 00059 { 00060 private: 00061 typedef actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction> JTAS; 00062 typedef JTAS::GoalHandle GoalHandle; 00063 typedef boost::shared_ptr<const control_msgs::FollowJointTrajectoryGoal> Goal; 00064 public: 00065 JointTrajectoryAction(const std::string& name); 00066 virtual ~JointTrajectoryAction(); 00067 00068 bool configureHook(); 00069 bool startHook(); 00070 void updateHook(); 00071 protected: 00072 RTT::OutputPort<trajectory_msgs::JointTrajectoryPoint> trajectoryPoint_port; 00073 00074 RTT::InputPort<bool> bufferReady_port; 00075 RTT::Property<int> numberOfJoints_prop; 00076 00077 RTT::InputPort<trajectory_msgs::JointTrajectory> command_port_; 00078 RTT::InputPort<bool> trajectoryCompleat_port; 00079 private: 00080 00081 void goalCB(GoalHandle gh); 00082 void cancelCB(GoalHandle gh); 00083 00084 void commandCB(); 00085 void compleatCB(); 00086 void bufferReadyCB(); 00087 00088 std::vector<trajectory_msgs::JointTrajectoryPoint > trajectory; 00089 std::vector<std::string> jointNames; 00090 unsigned int numberOfJoints; 00091 00092 unsigned int currentPoint; 00093 unsigned int endPoint; 00094 00095 actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction> as; 00096 bool goal_active; 00097 GoalHandle activeGoal; 00098 bool enable; 00099 }; 00100 00101 #endif /* JOINTTRAJECTORYACTION_H_ */