cartesian_pose.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_pose_controller.cpp
39  * Author: Michael Ferguson, Wim Meeussen
40  */
41 
44 
45 #include <urdf/model.h>
47 
48 #include <tf_conversions/tf_kdl.h>
49 
51 
52 namespace robot_controllers
53 {
54 
55 CartesianPoseController::CartesianPoseController() :
56  initialized_(false)
57 {
58 }
59 
61 {
62  // We absolutely need access to the controller manager
63  if (!manager)
64  {
65  initialized_ = false;
66  return -1;
67  }
68 
69  Controller::init(nh, manager);
70  manager_ = manager;
71 
72  // Initialize KDL structures
73  std::string tip_link;
74  nh.param<std::string>("root_name", root_link_, "torso_lift_link");
75  nh.param<std::string>("tip_name", tip_link, "gripper_link");
76 
77  // Load URDF
78  urdf::Model model;
79  if (!model.initParam("robot_description"))
80  {
81  ROS_ERROR("Failed to parse URDF");
82  return -1;
83  }
84 
85  // Load the tree
86  KDL::Tree kdl_tree;
87  if (!kdl_parser::treeFromUrdfModel(model, kdl_tree))
88  {
89  ROS_ERROR("Could not construct tree from URDF");
90  return -1;
91  }
92 
93  // Populate the chain
94  if(!kdl_tree.getChain(root_link_, tip_link, kdl_chain_))
95  {
96  ROS_ERROR("Could not construct chain from URDF");
97  return -1;
98  }
99 
105 
106  // Initialize controllers
107  robot_controllers::PID pid_controller;
108  if (!pid_controller.init(ros::NodeHandle(nh,"fb_trans"))) return false;
109  for (unsigned int i = 0; i < 3; i++)
110  pid_.push_back(pid_controller);
111  if (!pid_controller.init(ros::NodeHandle(nh,"fb_rot"))) return false;
112  for (unsigned int i = 0; i < 3; i++)
113  pid_.push_back(pid_controller);
114 
115  // Init joint handles
116  joints_.clear();
117  for (size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
120 
121  // Subscribe to command
122  command_sub_ = nh.subscribe<geometry_msgs::PoseStamped>("command", 1,
123  boost::bind(&CartesianPoseController::command, this, _1));
125 
126  // Feedback of twist
127  feedback_pub_ = nh.advertise<geometry_msgs::Twist>("feedback", 10);
128 
129  initialized_ = true;
130  return 0;
131 }
132 
134 {
135  if (!initialized_)
136  {
137  ROS_ERROR_NAMED("CartesianPoseController",
138  "Unable to start, not initialized.");
139  return false;
140  }
141 
143  {
144  ROS_ERROR_NAMED("CartesianPoseController",
145  "Unable to start, no goal.");
146  return false;
147  }
148 
149  return true;
150 }
151 
153 {
154  // Always stop
155  return true;
156 }
157 
159 {
160  // Simply stop
161  return (manager_->requestStop(getName()) == 0);
162 }
163 
165 {
166  // Need to initialize KDL structs
167  if (!initialized_)
168  return; // Should never actually hit this
169 
170  // Get current pose
171  actual_pose_ = getPose();
172 
173  // Pose feedback
175  geometry_msgs::Twist t;
176  t.linear.x = twist_error_(0);
177  t.linear.y = twist_error_(1);
178  t.linear.z = twist_error_(2);
179  t.angular.x = twist_error_(3);
180  t.angular.y = twist_error_(4);
181  t.angular.z = twist_error_(5);
183 
184  // Update PID
185  for (size_t i = 0; i < 6; ++i)
186  twist_error_(i) = pid_[i].update(twist_error_(i), dt.toSec());
187 
188  // Get jacobian
189  jac_solver_->JntToJac(jnt_pos_, jacobian_);
190 
191  // Convert wrench to joint efforts
192  for (size_t i = 0; i < kdl_chain_.getNrOfJoints(); ++i)
193  {
194  jnt_delta_(i) = 0.0;
195  for (unsigned int j = 0; j < 6; ++j)
196  jnt_delta_(i) += (jacobian_(j,i) * twist_error_(j));
197  }
198 
199  // Actually update joints
200  for (size_t j = 0; j < joints_.size(); ++j)
201  joints_[j]->setPosition(jnt_delta_(j) + joints_[j]->getPosition(), 0.0, 0.0);
202 }
203 
205 {
206  for (size_t i = 0; i < joints_.size(); ++i)
207  jnt_pos_(i) = joints_[i]->getPosition();
208 
210  jnt_to_pose_solver_->JntToCart(jnt_pos_, result);
211 
212  return result;
213 }
214 
215 void CartesianPoseController::command(const geometry_msgs::PoseStamped::ConstPtr& goal)
216 {
217  // Need to initialize KDL structs
218  if (!initialized_)
219  {
220  ROS_ERROR("CartesianPoseController: Cannot accept goal, controller is not initialized.");
221  return;
222  }
223 
224  // Need transform
225  if (!tf_.waitForTransform(goal->header.frame_id, root_link_,
226  goal->header.stamp, ros::Duration(0.1)))
227  {
228  ROS_ERROR_STREAM("CartesianPoseController: Unable to transform goal to " << root_link_ << ".");
229  return;
230  }
231 
232  // Update last command time before trying to start controller
234 
235  // Try to start up
236  if (manager_->requestStart(getName()) != 0)
237  {
238  ROS_ERROR("CartesianPoseController: Cannot start, blocked by another controller.");
239  return;
240  }
241 
242  tf::Stamped<tf::Pose> stamped;
243  tf::poseStampedMsgToTF(*goal, stamped);
244 
245  tf_.transformPose(root_link_, stamped, stamped);
246  tf::poseTFToKDL(stamped, desired_pose_);
247 }
248 
250 {
251  std::vector<std::string> names;
252  if (initialized_)
253  {
254  for (size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
256  names.push_back(kdl_chain_.getSegment(i).getJoint().getName());
257  }
258  return names;
259 }
260 
262 {
263  // Commanded == claimed
264  return getCommandedNames();
265 }
266 
267 
268 } // namespace robot_controllers
IMETHOD doubleVel diff(const doubleVel &a, const doubleVel &b, double dt=1.0)
result
const Segment & getSegment(unsigned int nr) const
void publish(const boost::shared_ptr< M > &message) const
std::vector< JointHandlePtr > joints_
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
void resize(unsigned int newNrOfColumns)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
unsigned int getNrOfSegments() const
virtual bool reset()
Cleanly reset the controller to it&#39;s initial state. Some controllers may choose to stop themselves...
virtual int requestStart(const std::string &name)
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
void poseTFToKDL(const tf::Pose &t, KDL::Frame &k)
virtual int requestStop(const std::string &name)
const std::string & getName() const
void command(const geometry_msgs::PoseStamped::ConstPtr &goal)
Controller command.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
boost::shared_ptr< KDL::ChainJntToJacSolver > jac_solver_
virtual bool start()
Attempt to start the controller. This should be called only by the ControllerManager instance...
const Joint & getJoint() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
unsigned int getNrOfJoints() const
virtual std::vector< std::string > getClaimedNames()
Get the names of joints/controllers which this controller exclusively claims.
virtual bool stop(bool force)
Attempt to stop the controller. This should be called only by the ControllerManager instance...
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
void resize(unsigned int newSize)
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
std::vector< robot_controllers::PID > pid_
boost::shared_ptr< KDL::ChainFkSolverPos > jnt_to_pose_solver_
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
void transformPose(const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
#define ROS_ERROR_NAMED(name,...)
virtual void update(const ros::Time &now, const ros::Duration &dt)
This is the update loop for the controller.
static Time now()
static void poseStampedMsgToTF(const geometry_msgs::PoseStamped &msg, Stamped< Pose > &bt)
JointHandlePtr getJointHandle(const std::string &name)
#define ROS_ERROR_STREAM(args)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)
bool init(const ros::NodeHandle &nh)
initialize gain settings from ROS parameter values
Definition: pid.cpp:68
const JointType & getType() const


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