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
00035
00036
00037
00038
00039
00040
00041
00042 #include <pluginlib/class_list_macros.h>
00043 #include <robot_controllers/cartesian_pose.h>
00044
00045 #include <urdf/model.h>
00046 #include <kdl_parser/kdl_parser.hpp>
00047
00048 #include <tf_conversions/tf_kdl.h>
00049
00050 PLUGINLIB_EXPORT_CLASS(robot_controllers::CartesianPoseController, robot_controllers::Controller)
00051
00052 namespace robot_controllers
00053 {
00054
00055 CartesianPoseController::CartesianPoseController() :
00056 initialized_(false)
00057 {
00058 }
00059
00060 int CartesianPoseController::init(ros::NodeHandle& nh, ControllerManager* manager)
00061 {
00062
00063 if (!manager)
00064 {
00065 initialized_ = false;
00066 return -1;
00067 }
00068
00069 Controller::init(nh, manager);
00070 manager_ = manager;
00071
00072
00073 std::string tip_link;
00074 nh.param<std::string>("root_name", root_link_, "torso_lift_link");
00075 nh.param<std::string>("tip_name", tip_link, "gripper_link");
00076
00077
00078 urdf::Model model;
00079 if (!model.initParam("robot_description"))
00080 {
00081 ROS_ERROR("Failed to parse URDF");
00082 return -1;
00083 }
00084
00085
00086 KDL::Tree kdl_tree;
00087 if (!kdl_parser::treeFromUrdfModel(model, kdl_tree))
00088 {
00089 ROS_ERROR("Could not construct tree from URDF");
00090 return -1;
00091 }
00092
00093
00094 if(!kdl_tree.getChain(root_link_, tip_link, kdl_chain_))
00095 {
00096 ROS_ERROR("Could not construct chain from URDF");
00097 return -1;
00098 }
00099
00100 jnt_to_pose_solver_.reset(new KDL::ChainFkSolverPos_recursive(kdl_chain_));
00101 jac_solver_.reset(new KDL::ChainJntToJacSolver(kdl_chain_));
00102 jnt_pos_.resize(kdl_chain_.getNrOfJoints());
00103 jnt_delta_.resize(kdl_chain_.getNrOfJoints());
00104 jacobian_.resize(kdl_chain_.getNrOfJoints());
00105
00106
00107 robot_controllers::PID pid_controller;
00108 if (!pid_controller.init(ros::NodeHandle(nh,"fb_trans"))) return false;
00109 for (unsigned int i = 0; i < 3; i++)
00110 pid_.push_back(pid_controller);
00111 if (!pid_controller.init(ros::NodeHandle(nh,"fb_rot"))) return false;
00112 for (unsigned int i = 0; i < 3; i++)
00113 pid_.push_back(pid_controller);
00114
00115
00116 joints_.clear();
00117 for (size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
00118 if (kdl_chain_.getSegment(i).getJoint().getType() != KDL::Joint::None)
00119 joints_.push_back(manager_->getJointHandle(kdl_chain_.getSegment(i).getJoint().getName()));
00120
00121
00122 command_sub_ = nh.subscribe<geometry_msgs::PoseStamped>("command", 1,
00123 boost::bind(&CartesianPoseController::command, this, _1));
00124 last_command_ = ros::Time(0);
00125
00126
00127 feedback_pub_ = nh.advertise<geometry_msgs::Twist>("feedback", 10);
00128
00129 initialized_ = true;
00130 return 0;
00131 }
00132
00133 bool CartesianPoseController::start()
00134 {
00135 if (!initialized_)
00136 {
00137 ROS_ERROR_NAMED("CartesianPoseController",
00138 "Unable to start, not initialized.");
00139 return false;
00140 }
00141
00142 if (ros::Time::now() - last_command_ > ros::Duration(3.0))
00143 {
00144 ROS_ERROR_NAMED("CartesianPoseController",
00145 "Unable to start, no goal.");
00146 return false;
00147 }
00148
00149 return true;
00150 }
00151
00152 bool CartesianPoseController::stop(bool force)
00153 {
00154
00155 return true;
00156 }
00157
00158 bool CartesianPoseController::reset()
00159 {
00160
00161 return (manager_->requestStop(getName()) == 0);
00162 }
00163
00164 void CartesianPoseController::update(const ros::Time& now, const ros::Duration& dt)
00165 {
00166
00167 if (!initialized_)
00168 return;
00169
00170
00171 actual_pose_ = getPose();
00172
00173
00174 twist_error_ = KDL::diff(actual_pose_, desired_pose_);
00175 geometry_msgs::Twist t;
00176 t.linear.x = twist_error_(0);
00177 t.linear.y = twist_error_(1);
00178 t.linear.z = twist_error_(2);
00179 t.angular.x = twist_error_(3);
00180 t.angular.y = twist_error_(4);
00181 t.angular.z = twist_error_(5);
00182 feedback_pub_.publish(t);
00183
00184
00185 for (size_t i = 0; i < 6; ++i)
00186 twist_error_(i) = pid_[i].update(twist_error_(i), dt.toSec());
00187
00188
00189 jac_solver_->JntToJac(jnt_pos_, jacobian_);
00190
00191
00192 for (size_t i = 0; i < kdl_chain_.getNrOfJoints(); ++i)
00193 {
00194 jnt_delta_(i) = 0.0;
00195 for (unsigned int j = 0; j < 6; ++j)
00196 jnt_delta_(i) += (jacobian_(j,i) * twist_error_(j));
00197 }
00198
00199
00200 for (size_t j = 0; j < joints_.size(); ++j)
00201 joints_[j]->setPosition(jnt_delta_(j) + joints_[j]->getPosition(), 0.0, 0.0);
00202 }
00203
00204 KDL::Frame CartesianPoseController::getPose()
00205 {
00206 for (size_t i = 0; i < joints_.size(); ++i)
00207 jnt_pos_(i) = joints_[i]->getPosition();
00208
00209 KDL::Frame result;
00210 jnt_to_pose_solver_->JntToCart(jnt_pos_, result);
00211
00212 return result;
00213 }
00214
00215 void CartesianPoseController::command(const geometry_msgs::PoseStamped::ConstPtr& goal)
00216 {
00217
00218 if (!initialized_)
00219 {
00220 ROS_ERROR("CartesianPoseController: Cannot accept goal, controller is not initialized.");
00221 return;
00222 }
00223
00224
00225 if (!tf_.waitForTransform(goal->header.frame_id, root_link_,
00226 goal->header.stamp, ros::Duration(0.1)))
00227 {
00228 ROS_ERROR_STREAM("CartesianPoseController: Unable to transform goal to " << root_link_ << ".");
00229 return;
00230 }
00231
00232
00233 last_command_ = ros::Time::now();
00234
00235
00236 if (manager_->requestStart(getName()) != 0)
00237 {
00238 ROS_ERROR("CartesianPoseController: Cannot start, blocked by another controller.");
00239 return;
00240 }
00241
00242 tf::Stamped<tf::Pose> stamped;
00243 tf::poseStampedMsgToTF(*goal, stamped);
00244
00245 tf_.transformPose(root_link_, stamped, stamped);
00246 tf::poseTFToKDL(stamped, desired_pose_);
00247 }
00248
00249 std::vector<std::string> CartesianPoseController::getCommandedNames()
00250 {
00251 std::vector<std::string> names;
00252 if (initialized_)
00253 {
00254 for (size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
00255 if (kdl_chain_.getSegment(i).getJoint().getType() != KDL::Joint::None)
00256 names.push_back(kdl_chain_.getSegment(i).getJoint().getName());
00257 }
00258 return names;
00259 }
00260
00261 std::vector<std::string> CartesianPoseController::getClaimedNames()
00262 {
00263
00264 return getCommandedNames();
00265 }
00266
00267
00268 }