$search
00001 00013 /************************************************************************ 00014 * Copyright (C) 2012 Eindhoven University of Technology (TU/e). * 00015 * All rights reserved. * 00016 ************************************************************************ 00017 * Redistribution and use in source and binary forms, with or without * 00018 * modification, are permitted provided that the following conditions * 00019 * are met: * 00020 * * 00021 * 1. Redistributions of source code must retain the above * 00022 * copyright notice, this list of conditions and the following * 00023 * disclaimer. * 00024 * * 00025 * 2. Redistributions in binary form must reproduce the above * 00026 * copyright notice, this list of conditions and the following * 00027 * disclaimer in the documentation and/or other materials * 00028 * provided with the distribution. * 00029 * * 00030 * THIS SOFTWARE IS PROVIDED BY TU/e "AS IS" AND ANY EXPRESS OR * 00031 * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * 00032 * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * 00033 * ARE DISCLAIMED. IN NO EVENT SHALL TU/e OR CONTRIBUTORS BE LIABLE * 00034 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR * 00035 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT * 00036 * OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; * 00037 * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF * 00038 * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * 00039 * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE * 00040 * USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH * 00041 * DAMAGE. * 00042 * * 00043 * The views and conclusions contained in the software and * 00044 * documentation are those of the authors and should not be * 00045 * interpreted as representing official policies, either expressed or * 00046 * implied, of TU/e. * 00047 ************************************************************************/ 00048 00049 // http://www.ros.org/wiki/pr2_mechanism 00050 // http://www.ros.org/wiki/pr2_mechanism/Tutorials 00051 00052 #include <cstring> 00053 #include <string> 00054 #include <iostream> 00055 #include <pr2_controller_interface/controller.h> 00056 #include <pr2_mechanism_model/joint.h> 00057 #include <ros/ros.h> 00058 #include <control_toolbox/pid.h> 00059 #include <std_srvs/Empty.h> 00060 #include <gazebo_msgs/ApplyBodyWrench.h> 00061 #include <gazebo_msgs/SetModelConfiguration.h> 00062 #include <gazebo_msgs/SetModelState.h> 00063 #include <gazebo_msgs/GetModelState.h> 00064 #include <gazebo_msgs/GetPhysicsProperties.h> 00065 #include <gazebo_msgs/SetPhysicsProperties.h> 00066 #include "tulip_gazebo/joint_state_message.h" 00067 #include <ros/console.h> // for ROS_DEBUG and ROS_INFO messages 00068 #include <time.h> 00069 #include <Simulator.hh> 00070 #define _USE_MATH_DEFINES 00071 #include <cmath> 00072 #include <LinearMath/btQuaternion.h> 00073 #include <LinearMath/btMatrix3x3.h> 00074 #include <tf/transform_broadcaster.h> 00075 00076 #define JOINT_PUBLISH_TIME 5 //seconds 00077 00078 namespace tulip_controller_namespace{ 00079 00080 00081 enum 00082 { 00083 //Here we declare the length of the storage buffer. 00084 //StoreLen = 8005 00085 00086 StoreLen = 16*100*JOINT_PUBLISH_TIME + 5 00087 //in the future read from parameters! 00088 //16000 samples corresponds to 16 joints * 100 times per second * 10 seconds time window, 5 extra samples to be sure 00089 }; 00090 00091 class tulip_controller_class: public pr2_controller_interface::Controller 00092 { 00093 private: 00094 00095 bool capture(); 00096 ros::Publisher joint_state_pub_; 00097 tulip_gazebo::joint_state_message storage_[StoreLen]; 00098 volatile int storage_index_; 00099 volatile int cycle_index_; 00100 std::vector<control_toolbox::Pid> pid_controller; 00101 pr2_mechanism_model::RobotState *robot_; 00102 ros::Time time_of_first_cycle_; 00103 ros::Time time_of_previous_cycle_; 00104 std::vector<pr2_mechanism_model::JointState*> joint_state; 00105 std::vector<pr2_mechanism_model::JointState*> backlash_state; 00106 std::vector<double> joint_pos_init; 00107 std::vector<double> joint_pos_desired; 00108 std::vector<double> joint_pos_current; 00109 std::vector<double> joint_pos_feedback; 00110 std::vector<std::string> joint_name; 00111 bool published_jointdata; 00112 00113 //create structure to store push force and initial orientation info 00114 struct xyz { 00115 double x; 00116 double y; 00117 double z; 00118 }; 00119 00120 struct rpy_prop { 00121 double roll; 00122 double pitch; 00123 double yaw; 00124 }; 00125 00126 struct quat_prop { 00127 double x; 00128 double y; 00129 double z; 00130 double w; 00131 }; 00132 00133 struct orientation_2types { 00134 quat_prop quaternion; 00135 rpy_prop rpy; 00136 }; 00137 00138 struct pose_properties { 00139 xyz position; 00140 orientation_2types orientation; 00141 }; 00142 00143 struct twist_properties { 00144 xyz linear; 00145 xyz angular; 00146 }; 00147 00148 struct init_model_state_properties { 00149 pose_properties pose; 00150 twist_properties twist; 00151 }; 00152 00153 struct push_properties { 00154 double time; 00155 double duration; 00156 xyz force; 00157 }; 00158 00159 00160 struct exp_properties { 00161 std::string name; 00162 init_model_state_properties init_model_state; 00163 push_properties push; 00164 }; 00165 00166 std::vector<exp_properties> exp; 00167 00168 public: 00169 virtual bool init(pr2_mechanism_model::RobotState *robot,ros::NodeHandle &n); 00170 virtual void starting(); 00171 virtual void update(); 00172 virtual void stopping(); 00173 00174 virtual bool getXyzPar (std::string xyz_name, xyz& xyz_var, ros::NodeHandle &n); 00175 virtual bool getExpPar (std::string exp_name, exp_properties& exp_var, ros::NodeHandle &n); 00176 virtual bool setExpState( exp_properties exp_var, ros::NodeHandle &n); 00177 virtual bool getRobotState(gazebo_msgs::GetModelState &srv_getstate, rpy_prop &cur_orient_rpy, ros::NodeHandle &n); 00178 virtual bool applyForcetoRobot(gazebo_msgs::ApplyBodyWrench &srv_wrench, ros::NodeHandle &n); 00179 virtual double getBacklashPosition(std::vector<pr2_mechanism_model::JointState*>& backlash_state, int i); 00180 virtual double getBacklashVelocity(std::vector<pr2_mechanism_model::JointState*>& backlash_state, int i); 00181 }; 00182 }