Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #include "tff_controller/tff_controller.h"
00035 #include <algorithm>
00036 #include <kdl/chainfksolvervel_recursive.hpp>
00037 #include <pluginlib/class_list_macros.h>
00038
00039
00040 PLUGINLIB_DECLARE_CLASS(tff_controller, TFFController, controller::TFFController, pr2_controller_interface::Controller)
00041
00042 using namespace KDL;
00043 using namespace ros;
00044
00045
00046
00047 namespace controller {
00048
00049 TFFController::TFFController()
00050 : robot_state_(NULL),
00051 jnt_to_twist_solver_(NULL),
00052 mode_(6),
00053 value_(6),
00054 twist_to_wrench_(6),
00055 state_position_publisher_(NULL)
00056 {}
00057
00058
00059
00060 TFFController::~TFFController()
00061 {}
00062
00063
00064
00065 bool TFFController::init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle& n)
00066 {
00067 node_ = n;
00068
00069
00070 std::string root_name, tip_name;
00071 if (!node_.getParam("root_name", root_name)){
00072 ROS_ERROR("TFFController: No root name found on parameter server");
00073 return false;
00074 }
00075 if (!node_.getParam("tip_name", tip_name)){
00076 ROS_ERROR("TFFController: No tip name found on parameter server");
00077 return false;
00078 }
00079
00080
00081 assert(robot_state);
00082 robot_state_ = robot_state;
00083
00084
00085 if (!chain_.init(robot_state, root_name, tip_name))
00086 return false;
00087 chain_.toKDL(kdl_chain_);
00088
00089
00090 jnt_to_twist_solver_.reset(new ChainFkSolverVel_recursive(kdl_chain_));
00091 jnt_posvel_.resize(kdl_chain_.getNrOfJoints());
00092 jnt_to_jac_solver_.reset(new ChainJntToJacSolver(kdl_chain_));
00093 jnt_pos_.resize(kdl_chain_.getNrOfJoints());
00094 jnt_eff_.resize(kdl_chain_.getNrOfJoints());
00095 jacobian_.resize(kdl_chain_.getNrOfJoints());
00096
00097
00098 double trans, rot;
00099 node_.param("twist_to_wrench_trans", trans, 0.0);
00100 for (unsigned int i=0; i<3; i++)
00101 twist_to_wrench_[i] = trans;
00102 node_.param("twist_to_wrench_rot", rot, 0.0);
00103 for (unsigned int i=3; i<6; i++)
00104 twist_to_wrench_[i] = rot;
00105
00106
00107 control_toolbox::Pid pid_controller;
00108 if (!pid_controller.init(NodeHandle(node_, "vel_trans"))) return false;
00109 for (unsigned int i=0; i<3; i++)
00110 vel_pid_controller_.push_back(pid_controller);
00111
00112 if (!pid_controller.init(NodeHandle(node_, "vel_rot"))) return false;
00113 for (unsigned int i=0; i<3; i++)
00114 vel_pid_controller_.push_back(pid_controller);
00115
00116 if (!pid_controller.init(NodeHandle(node_, "pos_trans"))) return false;
00117 for (unsigned int i=0; i<3; i++)
00118 pos_pid_controller_.push_back(pid_controller);
00119
00120 if (!pid_controller.init(NodeHandle(node_, "pos_rot"))) return false;
00121 for (unsigned int i=0; i<3; i++)
00122 pos_pid_controller_.push_back(pid_controller);
00123
00124
00125 sub_command_ = node_.subscribe<tff_controller::TaskFrameFormalism>("command", 1,
00126 &TFFController::command, this);
00127
00128
00129 state_position_publisher_.reset(new realtime_tools::RealtimePublisher<geometry_msgs::Twist>(node_, "state/position", 1));
00130
00131 return true;
00132 }
00133
00134
00135
00136 void TFFController::starting()
00137 {
00138
00139 last_time_ = robot_state_->getTime();
00140
00141
00142 for (unsigned int i=0; i<6; i++){
00143 mode_[i] = tff_controller::TaskFrameFormalism::FORCE;
00144 value_[i] = 0;
00145 }
00146
00147
00148 for (unsigned int i=0; i<6; i++){
00149 vel_pid_controller_[i].reset();
00150 pos_pid_controller_[i].reset();
00151 }
00152
00153
00154 FrameVel frame_twist;
00155 chain_.getVelocities(jnt_posvel_);
00156 jnt_to_twist_solver_->JntToCart(jnt_posvel_, frame_twist);
00157 pose_meas_old_ = frame_twist.value();
00158 position_ = Twist::Zero();
00159
00160
00161 wrench_desi_ = Wrench::Zero();
00162
00163 loop_count_ = 0;
00164 }
00165
00166
00167 void TFFController::update()
00168 {
00169
00170 ros::Time time = robot_state_->getTime();
00171 ros::Duration dt = time - last_time_;
00172 last_time_ = time;
00173
00174
00175 chain_.getPositions(jnt_pos_);
00176
00177
00178 chain_.getVelocities(jnt_posvel_);
00179
00180
00181 jnt_to_jac_solver_->JntToJac(jnt_pos_, jacobian_);
00182
00183
00184 FrameVel frame_twist;
00185 jnt_to_twist_solver_->JntToCart(jnt_posvel_, frame_twist);
00186 pose_meas_ = frame_twist.value();
00187 twist_meas_ = pose_meas_.M.Inverse() * (frame_twist.deriv());
00188
00189
00190 position_ += pose_meas_.M.Inverse() * diff(pose_meas_old_, pose_meas_);
00191 pose_meas_old_ = pose_meas_;
00192
00193
00194 wrench_desi_ = Wrench::Zero();
00195 for (unsigned int i=0; i<6; i++){
00196 if (mode_[i] == tff_controller::TaskFrameFormalism::FORCE)
00197 wrench_desi_[i] = value_[i];
00198 else if (mode_[i] == tff_controller::TaskFrameFormalism::VELOCITY)
00199 wrench_desi_[i] = twist_to_wrench_[i] * (value_[i] + vel_pid_controller_[i].updatePid(twist_meas_[i] - value_[i], dt));
00200 else if (mode_[i] == tff_controller::TaskFrameFormalism::POSITION)
00201 wrench_desi_[i] = twist_to_wrench_[i] * (pos_pid_controller_[i].updatePid(position_[i] - value_[i], dt));
00202 }
00203
00204
00205 wrench_desi_ = (pose_meas_.M * wrench_desi_);
00206
00207
00208 for (unsigned int i = 0; i < kdl_chain_.getNrOfJoints(); i++){
00209 jnt_eff_(i) = 0;
00210 for (unsigned int j=0; j<6; j++)
00211 jnt_eff_(i) += (jacobian_(j,i) * wrench_desi_(j));
00212 }
00213
00214
00215 chain_.setEfforts(jnt_eff_);
00216
00217
00218 if (++loop_count_ % 100 == 0){
00219 if (state_position_publisher_){
00220 if (state_position_publisher_->trylock()){
00221 state_position_publisher_->msg_.linear.x = position_.vel(0);
00222 state_position_publisher_->msg_.linear.y = position_.vel(1);
00223 state_position_publisher_->msg_.linear.z = position_.vel(2);
00224 state_position_publisher_->msg_.angular.x = position_.rot(0);
00225 state_position_publisher_->msg_.angular.y = position_.rot(1);
00226 state_position_publisher_->msg_.angular.z = position_.rot(2);
00227 state_position_publisher_->unlockAndPublish();
00228 }
00229 }
00230 }
00231
00232 }
00233
00234
00235 void TFFController::command(const tff_controller::TaskFrameFormalismConstPtr& tff_msg)
00236 {
00237 mode_[0] = trunc(tff_msg->mode.linear.x);
00238 mode_[1] = trunc(tff_msg->mode.linear.y);
00239 mode_[2] = trunc(tff_msg->mode.linear.z);
00240 mode_[3] = trunc(tff_msg->mode.angular.x);
00241 mode_[4] = trunc(tff_msg->mode.angular.y);
00242 mode_[5] = trunc(tff_msg->mode.angular.z);
00243
00244 value_[0] = tff_msg->value.linear.x;
00245 value_[1] = tff_msg->value.linear.y;
00246 value_[2] = tff_msg->value.linear.z;
00247 value_[3] = tff_msg->value.angular.x;
00248 value_[4] = tff_msg->value.angular.y;
00249 value_[5] = tff_msg->value.angular.z;
00250 }
00251
00252
00253
00254 };