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 #include <pluginlib/class_list_macros.h>
00039 #include <robot_controllers/gravity_compensation.h>
00040
00041 PLUGINLIB_EXPORT_CLASS(robot_controllers::GravityCompensation, robot_controllers::Controller)
00042
00043 namespace robot_controllers
00044 {
00045
00046 int GravityCompensation::init(ros::NodeHandle& nh, ControllerManager* manager)
00047 {
00048 Controller::init(nh, manager);
00049 manager_ = manager;
00050
00051
00052 urdf::Model model;
00053 if (!model.initParam("robot_description"))
00054 {
00055 ROS_ERROR("Failed to parse URDF");
00056 return -1;
00057 }
00058
00059
00060 KDL::Tree kdl_tree;
00061 if (!kdl_parser::treeFromUrdfModel(model, kdl_tree))
00062 {
00063 ROS_ERROR("Could not construct tree from URDF");
00064 return -1;
00065 }
00066
00067
00068 std::string root, tip;
00069 nh.param<std::string>("root", root, "torso_lift_link");
00070 nh.param<std::string>("tip", tip, "wrist_roll_link");
00071 if(!kdl_tree.getChain(root, tip, kdl_chain_))
00072 {
00073 ROS_ERROR("Could not construct chain from URDF");
00074 return -1;
00075 }
00076
00077 kdl_chain_dynamics_.reset(new KDL::ChainDynParam(kdl_chain_, KDL::Vector(0,0,-9.81)));
00078
00079
00080 positions_ = KDL::JntArrayVel(kdl_chain_.getNrOfJoints());
00081 KDL::SetToZero(positions_.q);
00082 KDL::SetToZero(positions_.qdot);
00083
00084
00085 joints_.clear();
00086 for (size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
00087 if (kdl_chain_.getSegment(i).getJoint().getType() != KDL::Joint::None)
00088 joints_.push_back(manager_->getJointHandle(kdl_chain_.getSegment(i).getJoint().getName()));
00089
00090 initialized_ = true;
00091
00092
00093 bool autostart;
00094 nh.param("autostart", autostart, false);
00095 if (autostart)
00096 manager->requestStart(getName());
00097
00098 return 0;
00099 }
00100
00101 bool GravityCompensation::start()
00102 {
00103 if (!initialized_)
00104 return false;
00105 return true;
00106 }
00107
00108 void GravityCompensation::update(const ros::Time& time, const ros::Duration& dt)
00109 {
00110
00111 if (!initialized_)
00112 return;
00113
00114
00115 for (size_t i = 0; i < kdl_chain_.getNrOfJoints(); ++i)
00116 positions_.q.data[i] = joints_[i]->getPosition();
00117
00118
00119 KDL::JntArray torques(kdl_chain_.getNrOfJoints());
00120 kdl_chain_dynamics_->JntToGravity(positions_.q, torques);
00121
00122
00123 for (size_t i = 0; i < kdl_chain_.getNrOfJoints(); ++i)
00124 joints_[i]->setEffort(torques.data[i]);
00125 }
00126
00127 std::vector<std::string> GravityCompensation::getCommandedNames()
00128 {
00129 std::vector<std::string> names;
00130 if (initialized_)
00131 {
00132 for (size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
00133 if (kdl_chain_.getSegment(i).getJoint().getType() != KDL::Joint::None)
00134 names.push_back(kdl_chain_.getSegment(i).getJoint().getName());
00135 }
00136 return names;
00137 }
00138
00139 std::vector<std::string> GravityCompensation::getClaimedNames()
00140 {
00141
00142 std::vector<std::string> names;
00143 return names;
00144 }
00145
00146 }