cartesian_wrench.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  * Copyright (c) 2008, Willow Garage, Inc.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Unbounded Robotics nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *********************************************************************/
36 
37 /*
38  * Derived a bit from pr2_controllers/cartesian_wrench_controller.cpp
39  * Author: Michael Ferguson, Wim Meeussen
40  */
41 
44 
45 #include <urdf/model.h>
47 
49 
50 namespace robot_controllers
51 {
52 
53 CartesianWrenchController::CartesianWrenchController() :
54  initialized_(false)
55 {
56 }
57 
59 {
60  // We absolutely need access to the controller manager
61  if (!manager)
62  {
63  initialized_ = false;
64  return -1;
65  }
66 
67  Controller::init(nh, manager);
68  manager_ = manager;
69 
70  // Initialize KDL structures
71  std::string tip_link;
72  nh.param<std::string>("root_name", root_link_, "torso_lift_link");
73  nh.param<std::string>("tip_name", tip_link, "gripper_link");
74 
75  // Load URDF
76  urdf::Model model;
77  if (!model.initParam("robot_description"))
78  {
79  ROS_ERROR("Failed to parse URDF");
80  return -1;
81  }
82 
83  // Load the tree
84  KDL::Tree kdl_tree;
85  if (!kdl_parser::treeFromUrdfModel(model, kdl_tree))
86  {
87  ROS_ERROR("Could not construct tree from URDF");
88  return -1;
89  }
90 
91  // Populate the chain
92  if(!kdl_tree.getChain(root_link_, tip_link, kdl_chain_))
93  {
94  ROS_ERROR("Could not construct chain from URDF");
95  return -1;
96  }
97 
102 
103  // Init joint handles
104  joints_.clear();
105  for (size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
108 
109  // Subscribe to command
110  command_sub_ = nh.subscribe<geometry_msgs::Wrench>("command", 1,
111  boost::bind(&CartesianWrenchController::command, this, _1));
113 
114  initialized_ = true;
115  return 0;
116 }
117 
119 {
120  if (!initialized_)
121  {
122  ROS_ERROR_NAMED("CartesianWrenchController",
123  "Unable to start, not initialized.");
124  return false;
125  }
126 
128  {
129  ROS_ERROR_NAMED("CartesianWrenchController",
130  "Unable to start, no goal.");
131  return false;
132  }
133 
134  return true;
135 }
136 
138 {
139  return true;
140 }
141 
143 {
144  // Simply stop
145  return (manager_->requestStop(getName()) == 0);
146 }
147 
149 {
150  // Need to initialize KDL structs
151  if (!initialized_)
152  return;
153 
155  {
156  // Command has timed out, shutdown
158  return;
159  }
160 
161  // This updates jnt_pos_
162  updateJoints();
163 
164  // Get jacobian
165  jac_solver_->JntToJac(jnt_pos_, jacobian_);
166 
167  // Convert wrench to joint efforts
168  for (size_t i = 0; i < kdl_chain_.getNrOfJoints(); ++i)
169  {
170  jnt_eff_(i) = 0;
171  for (unsigned int j = 0; j < 6; ++j)
172  jnt_eff_(i) += (jacobian_(j,i) * desired_wrench_(j));
173  }
174 
175  // Actually update joints
176  for (size_t j = 0; j < joints_.size(); ++j)
177  joints_[j]->setEffort(jnt_eff_(j));
178 }
179 
181 {
182  for (size_t i = 0; i < joints_.size(); ++i)
183  jnt_pos_(i) = joints_[i]->getPosition();
184 }
185 
186 void CartesianWrenchController::command(const geometry_msgs::Wrench::ConstPtr& goal)
187 {
188  // Update command
189  desired_wrench_.force(0) = goal->force.x;
190  desired_wrench_.force(1) = goal->force.y;
191  desired_wrench_.force(2) = goal->force.z;
192  desired_wrench_.torque(0) = goal->torque.x;
193  desired_wrench_.torque(1) = goal->torque.y;
194  desired_wrench_.torque(2) = goal->torque.z;
195 
196  // Update last command time before trying to start controller
198 
199  // Try to start up
200  if (manager_->requestStart(getName()) != 0)
201  {
202  ROS_ERROR("CartesianWrenchController: Cannot start, blocked by another controller.");
203  return;
204  }
205 }
206 
208 {
209  std::vector<std::string> names;
210  if (initialized_)
211  {
212  for (size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
214  names.push_back(kdl_chain_.getSegment(i).getJoint().getName());
215  }
216  return names;
217 }
218 
220 {
221  return getCommandedNames();
222 }
223 
224 } // namespace robot_controllers
const Segment & getSegment(unsigned int nr) const
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
void resize(unsigned int newNrOfColumns)
virtual bool start()
Attempt to start the controller. This should be called only by the ControllerManager instance...
virtual void update(const ros::Time &now, const ros::Duration &dt)
This is the update loop for the controller.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
unsigned int getNrOfSegments() const
virtual int requestStart(const std::string &name)
Vector torque
double z() const
virtual int requestStop(const std::string &name)
const std::string & getName() const
double y() const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void command(const geometry_msgs::Wrench::ConstPtr &goal)
Controller command.
double x() const
const Joint & getJoint() const
unsigned int getNrOfJoints() const
boost::shared_ptr< KDL::ChainJntToJacSolver > jac_solver_
Vector force
void resize(unsigned int newSize)
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
#define ROS_ERROR_NAMED(name,...)
static Time now()
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
JointHandlePtr getJointHandle(const std::string &name)
virtual bool stop(bool force)
Attempt to stop the controller. This should be called only by the ControllerManager instance...
virtual bool reset()
Cleanly reset the controller to it&#39;s initial state. Some controllers may choose to stop themselves...
virtual std::vector< std::string > getClaimedNames()
Get the names of joints/controllers which this controller exclusively claims.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)
const JointType & getType() const


robot_controllers
Author(s): Michael Ferguson
autogenerated on Sun Sep 27 2020 03:22:39