$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 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 Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 /* 00031 * Author: Wim Meeussen 00032 */ 00033 00034 #ifndef CARTESIAN_TRAJECTORY_CONTROLLER_H 00035 #define CARTESIAN_TRAJECTORY_CONTROLLER_H 00036 00037 #include <vector> 00038 #include <string> 00039 #include <kdl/chain.hpp> 00040 #include <kdl/frames.hpp> 00041 #include <kdl/velocityprofile_trap.hpp> 00042 #include <tf/transform_listener.h> 00043 #include <tf/message_filter.h> 00044 #include <ros/ros.h> 00045 #include <geometry_msgs/PoseStamped.h> 00046 #include <pr2_controller_interface/controller.h> 00047 #include <robot_mechanism_controllers/cartesian_pose_controller.h> 00048 #include <pr2_manipulation_controllers/MoveToPose.h> 00049 #include <std_srvs/Empty.h> 00050 #include <boost/scoped_ptr.hpp> 00051 00052 using namespace controller; 00053 00054 namespace pr2_manipulation_controllers { 00055 00056 00057 class CartesianTrajectoryController : public pr2_controller_interface::Controller 00058 { 00059 public: 00060 CartesianTrajectoryController(); 00061 ~CartesianTrajectoryController(); 00062 00063 bool init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle& n); 00064 00065 void starting(); 00066 void update(); 00067 bool moveTo(const geometry_msgs::PoseStamped& pose, 00068 const geometry_msgs::Twist& tolerance=geometry_msgs::Twist(), double duration=0); 00069 bool checkMoving(pr2_manipulation_controllers::CheckMoving::Request &req, pr2_manipulation_controllers::CheckMoving::Response &res); 00070 00071 private: 00072 KDL::Frame getPose(); 00073 void TransformToFrame(const tf::Transform& trans, KDL::Frame& frame); 00074 00075 // topic 00076 void command(const tf::MessageFilter<geometry_msgs::PoseStamped>::MConstPtr& pose_msg); 00077 00078 // service calls 00079 bool moveTo(pr2_manipulation_controllers::MoveToPose::Request &req, pr2_manipulation_controllers::MoveToPose::Response &resp); 00080 bool preempt(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp); 00081 00082 ros::NodeHandle node_; 00083 ros::ServiceServer move_to_srv_, preempt_srv_, check_moving_srv_; 00084 00085 std::string controller_name_; 00086 ros::Time last_time_, time_started_; 00087 double time_passed_, max_duration_; 00088 bool is_moving_, request_preempt_, exceed_tolerance_; 00089 00090 KDL::Frame pose_begin_, pose_end_, pose_current_; 00091 KDL::Twist twist_current_, tolerance_; 00092 00093 // robot structure 00094 pr2_mechanism_model::RobotState *robot_state_; 00095 pr2_mechanism_model::Chain chain_; 00096 00097 // kdl stuff for kinematics 00098 KDL::Chain kdl_chain_; 00099 boost::scoped_ptr<KDL::ChainFkSolverPos> jnt_to_pose_solver_; 00100 KDL::JntArray jnt_pos_; 00101 00102 // motion profiles 00103 std::vector<KDL::VelocityProfile_Trap> motion_profile_; 00104 00105 // pose controller 00106 CartesianPoseController* pose_controller_; 00107 00108 tf::TransformListener tf_; 00109 //boost::scoped_ptr<tf::MessageFilter<geometry_msgs::PoseStamped> > command_notifier_; 00110 //ros::Subscriber command_sub_; 00111 00112 std::string root_name_; 00113 }; 00114 00115 00116 } 00117 #endif