gravity_compensation.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014, Fetch Robotics Inc.
5  * Copyright (c) 2013, Unbounded Robotics Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Unbounded Robotics nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Michael Ferguson */
37 
40 
42 
43 namespace robot_controllers
44 {
45 
47 {
48  Controller::init(nh, manager);
49  manager_ = manager;
50 
51  // Load URDF
52  urdf::Model model;
53  if (!model.initParam("robot_description"))
54  {
55  ROS_ERROR("Failed to parse URDF");
56  return -1;
57  }
58 
59  // Load the tree
60  KDL::Tree kdl_tree;
61  if (!kdl_parser::treeFromUrdfModel(model, kdl_tree))
62  {
63  ROS_ERROR("Could not construct tree from URDF");
64  return -1;
65  }
66 
67  // Populate the Chain
68  std::string root, tip;
69  nh.param<std::string>("root", root, "torso_lift_link");
70  nh.param<std::string>("tip", tip, "wrist_roll_link");
71  if(!kdl_tree.getChain(root, tip, kdl_chain_))
72  {
73  ROS_ERROR("Could not construct chain from URDF");
74  return -1;
75  }
76 
78 
79  // Init positions
83 
84  // Init Joint Handles
85  joints_.clear();
86  for (size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
89 
90  initialized_ = true;
91 
92  // Should we autostart?
93  bool autostart;
94  nh.param("autostart", autostart, false);
95  if (autostart)
96  manager->requestStart(getName());
97 
98  return 0;
99 }
100 
102 {
103  if (!initialized_)
104  return false;
105  return true;
106 }
107 
109 {
110  // Need to initialize KDL structs
111  if (!initialized_)
112  return;
113 
114  // Get current positions
115  for (size_t i = 0; i < kdl_chain_.getNrOfJoints(); ++i)
116  positions_.q.data[i] = joints_[i]->getPosition();
117 
118  // Do the gravity compensation
120  kdl_chain_dynamics_->JntToGravity(positions_.q, torques);
121 
122  // Update effort command
123  for (size_t i = 0; i < kdl_chain_.getNrOfJoints(); ++i)
124  joints_[i]->setEffort(torques.data[i]);
125 }
126 
127 std::vector<std::string> GravityCompensation::getCommandedNames()
128 {
129  std::vector<std::string> names;
130  if (initialized_)
131  {
132  for (size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
134  names.push_back(kdl_chain_.getSegment(i).getJoint().getName());
135  }
136  return names;
137 }
138 
139 std::vector<std::string> GravityCompensation::getClaimedNames()
140 {
141  // We don't claim anything
142  std::vector<std::string> names;
143  return names;
144 }
145 
146 } // namespace robot_controllers
Controller which uses KDL to compute torque needed for static holding of the chain at the current pos...
virtual void update(const ros::Time &time, const ros::Duration &dt)
This is the update loop for the controller.
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
unsigned int getNrOfSegments() const
const Segment & getSegment(unsigned int nr) const
virtual std::vector< std::string > getClaimedNames()
Get the names of joints/controllers which this controller exclusively claims.
#define ROS_ERROR(...)
virtual int requestStart(const std::string &name)
const Joint & getJoint() const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
unsigned int getNrOfJoints() const
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
KDL::Chain kdl_chain_
is KDL structure setup
Eigen::VectorXd data
boost::shared_ptr< KDL::ChainDynParam > kdl_chain_dynamics_
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
URDF_EXPORT bool initParam(const std::string &param)
const JointType & getType() const
virtual bool start()
Attempt to start the controller. This should be called only by the ControllerManager instance...
void SetToZero(Jacobian &jac)
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
std::vector< JointHandlePtr > joints_
const std::string & getName() const
JointHandlePtr getJointHandle(const std::string &name)
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)


robot_controllers
Author(s): Michael Ferguson
autogenerated on Mon Feb 28 2022 23:26:08