cartesian_pose_controller.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /*
31  * Author: Wim Meeussen
32  */
33 
34 
35 #include <boost/bind.hpp>
36 
38 #include <algorithm>
39 #include "kdl/chainfksolverpos_recursive.hpp"
41 #include "tf_conversions/tf_kdl.h"
42 
43 
44 using namespace KDL;
45 using namespace tf;
46 using namespace std;
47 
49 
50 namespace controller {
51 
52 CartesianPoseController::CartesianPoseController()
53 : robot_state_(NULL)
54 {}
55 
57 {
58  command_filter_.reset();
59 }
60 
61 
63 {
64  node_ = n;
65 
66  // get name of root and tip from the parameter server
67  std::string tip_name;
68  if (!node_.getParam("root_name", root_name_)){
69  ROS_ERROR("CartesianPoseController: No root name found on parameter server (namespace: %s)",
70  node_.getNamespace().c_str());
71  return false;
72  }
73  if (!node_.getParam("tip_name", tip_name)){
74  ROS_ERROR("CartesianPoseController: No tip name found on parameter server (namespace: %s)",
75  node_.getNamespace().c_str());
76  return false;
77  }
78 
79  // test if we got robot pointer
80  assert(robot_state);
81  robot_state_ = robot_state;
82 
83  // create robot chain from root to tip
84  if (!chain_.init(robot_state_, root_name_, tip_name))
85  return false;
86  if (!chain_.allCalibrated())
87  {
88  ROS_ERROR("Not all joints in the chain are calibrated (namespace: %s)", node_.getNamespace().c_str());
89  return false;
90  }
92 
93  // create solver
94  jnt_to_pose_solver_.reset(new ChainFkSolverPos_recursive(kdl_chain_));
95  jac_solver_.reset(new ChainJntToJacSolver(kdl_chain_));
96  jnt_pos_.resize(kdl_chain_.getNrOfJoints());
97  jnt_eff_.resize(kdl_chain_.getNrOfJoints());
98  jacobian_.resize(kdl_chain_.getNrOfJoints());
99 
100  // create pid controller for the translation and for the rotation
101  control_toolbox::Pid pid_controller;
102  if (!pid_controller.init(ros::NodeHandle(node_,"fb_trans"))) return false;
103  for (unsigned int i = 0; i < 3; i++)
104  pid_controller_.push_back(pid_controller);
105  if (!pid_controller.init(ros::NodeHandle(node_,"fb_rot"))) return false;
106  for (unsigned int i = 0; i < 3; i++)
107  pid_controller_.push_back(pid_controller);
108 
109  // subscribe to pose commands
110  sub_command_.subscribe(node_, "command", 10);
112  sub_command_, tf_, root_name_, 10, node_));
113  command_filter_->registerCallback(boost::bind(&CartesianPoseController::command, this, _1));
114 
115  // realtime publisher for control state
118 
119  return true;
120 }
121 
123 {
124  // reset pid controllers
125  for (unsigned int i=0; i<6; i++)
126  pid_controller_[i].reset();
127 
128  // initialize desired pose/twist
129  twist_ff_ = Twist::Zero();
130  pose_desi_ = getPose();
132 
133  loop_count_ = 0;
134 }
135 
136 
137 
139 {
140  // get time
141  ros::Time time = robot_state_->getTime();
142  ros::Duration dt = time - last_time_;
143  last_time_ = time;
144 
145  // get current pose
146  pose_meas_ = getPose();
147 
148  // pose feedback into twist
150  KDL::Wrench wrench_desi;
151  for (unsigned int i=0; i<6; i++)
152  wrench_desi(i) = pid_controller_[i].computeCommand(twist_error_(i), dt);
153 
154  // get the chain jacobian
155  jac_solver_->JntToJac(jnt_pos_, jacobian_);
156 
157  // Converts the wrench into joint efforts with a jacbobian-transpose
158  for (unsigned int i = 0; i < kdl_chain_.getNrOfJoints(); i++){
159  jnt_eff_(i) = 0;
160  for (unsigned int j=0; j<6; j++)
161  jnt_eff_(i) += (jacobian_(j,i) * wrench_desi(j));
162  }
163 
164  // set effort to joints
166 
167 
168  if (++loop_count_ % 100 == 0){
170  if (state_error_publisher_->trylock()){
171  state_error_publisher_->msg_.linear.x = twist_error_.vel(0);
172  state_error_publisher_->msg_.linear.y = twist_error_.vel(1);
173  state_error_publisher_->msg_.linear.z = twist_error_.vel(2);
174  state_error_publisher_->msg_.angular.x = twist_error_.rot(0);
175  state_error_publisher_->msg_.angular.y = twist_error_.rot(1);
176  state_error_publisher_->msg_.angular.z = twist_error_.rot(2);
177  state_error_publisher_->unlockAndPublish();
178  }
179  }
181  if (state_pose_publisher_->trylock()){
182  Pose tmp;
184  poseStampedTFToMsg(Stamped<Pose>(tmp, ros::Time::now(), root_name_), state_pose_publisher_->msg_);
185  state_pose_publisher_->unlockAndPublish();
186  }
187  }
188  }
189 }
190 
191 
192 
194 {
195  // get the joint positions and velocities
197 
198  // get cartesian pose
199  Frame result;
200  jnt_to_pose_solver_->JntToCart(jnt_pos_, result);
201 
202  return result;
203 }
204 
205 void CartesianPoseController::command(const geometry_msgs::PoseStamped::ConstPtr& pose_msg)
206 {
207  // convert message to transform
208  Stamped<Pose> pose_stamped;
209  poseStampedMsgToTF(*pose_msg, pose_stamped);
210 
211  // convert to reference frame of root link of the controller chain
212  tf_.transformPose(root_name_, pose_stamped, pose_stamped);
213  tf::poseTFToKDL(pose_stamped, pose_desi_);
214 }
215 
216 } // namespace
217 
controller::CartesianPoseController::command_filter_
boost::scoped_ptr< tf::MessageFilter< geometry_msgs::PoseStamped > > command_filter_
Definition: cartesian_pose_controller.h:144
pr2_mechanism_model::Chain::addEfforts
void addEfforts(const Vec &v)
controller::CartesianPoseController::root_name_
std::string root_name_
Definition: cartesian_pose_controller.h:119
tf::poseTFToKDL
void poseTFToKDL(const tf::Pose &t, KDL::Frame &k)
controller::CartesianPoseController::kdl_chain_
KDL::Chain kdl_chain_
Definition: cartesian_pose_controller.h:130
controller::CartesianPoseController::tf_
tf::TransformListener tf_
Definition: cartesian_pose_controller.h:142
controller::CartesianPoseController::init
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Definition: cartesian_pose_controller.cpp:62
i
int i
controller::CartesianPoseController::twist_error_
KDL::Twist twist_error_
Definition: cartesian_pose_controller.h:113
controller::CartesianPoseController::sub_command_
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_command_
Definition: cartesian_pose_controller.h:143
tf::TransformListener::transformPose
void transformPose(const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
controller::CartesianPoseController::update
void update()
Definition: cartesian_pose_controller.cpp:138
controller::CartesianPoseController::starting
void starting()
Definition: cartesian_pose_controller.cpp:122
controller::CartesianPoseController::robot_state_
pr2_mechanism_model::RobotState * robot_state_
Definition: cartesian_pose_controller.h:123
controller::CartesianPoseController::chain_
pr2_mechanism_model::Chain chain_
Definition: cartesian_pose_controller.h:124
controller::CartesianPoseController::~CartesianPoseController
~CartesianPoseController()
Definition: cartesian_pose_controller.cpp:56
pr2_mechanism_model::Chain::getPositions
void getPositions(KDL::JntArray &)
controller::CartesianPoseController::jnt_pos_
KDL::JntArray jnt_pos_
Definition: cartesian_pose_controller.h:133
controller::CartesianPoseController::jnt_to_pose_solver_
boost::scoped_ptr< KDL::ChainFkSolverPos > jnt_to_pose_solver_
Definition: cartesian_pose_controller.h:131
controller::CartesianPoseController::state_pose_publisher_
boost::scoped_ptr< realtime_tools::RealtimePublisher< geometry_msgs::PoseStamped > > state_pose_publisher_
Definition: cartesian_pose_controller.h:139
controller::CartesianPoseController::jac_solver_
boost::scoped_ptr< KDL::ChainJntToJacSolver > jac_solver_
Definition: cartesian_pose_controller.h:132
controller::CartesianPoseController::pid_controller_
std::vector< control_toolbox::Pid > pid_controller_
Definition: cartesian_pose_controller.h:127
controller::CartesianPoseController::twist_ff_
KDL::Twist twist_ff_
Definition: cartesian_pose_controller.h:110
tf::Stamped
realtime_tools::RealtimePublisher
controller::CartesianPoseController::loop_count_
unsigned int loop_count_
Definition: cartesian_pose_controller.h:140
controller
pr2_mechanism_model::RobotState
control_toolbox::Pid::init
bool init(const ros::NodeHandle &n, const bool quiet=false)
tf::poseKDLToTF
void poseKDLToTF(const KDL::Frame &k, tf::Pose &t)
pr2_mechanism_model::Chain::allCalibrated
bool allCalibrated()
ROS_ERROR
#define ROS_ERROR(...)
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
controller::CartesianPoseController::jnt_eff_
KDL::JntArray jnt_eff_
Definition: cartesian_pose_controller.h:134
tf::Transform
controller::CartesianPoseController::state_error_publisher_
boost::scoped_ptr< realtime_tools::RealtimePublisher< geometry_msgs::Twist > > state_error_publisher_
Definition: cartesian_pose_controller.h:138
controller::CartesianPoseController::jacobian_
KDL::Jacobian jacobian_
Definition: cartesian_pose_controller.h:135
controller::CartesianPoseController
Definition: cartesian_pose_controller.h:96
pr2_controller_interface::Controller
pr2_mechanism_model::Chain::toKDL
void toKDL(KDL::Chain &chain)
message_filters::Subscriber::subscribe
void subscribe()
pr2_mechanism_model::RobotState::getTime
ros::Time getTime()
ros::Time
std
tf::MessageFilter
controller::CartesianPoseController::pose_meas_
KDL::Frame pose_meas_
Definition: cartesian_pose_controller.h:109
class_list_macros.hpp
tf_kdl.h
controller::CartesianPoseController::pose_desi_
KDL::Frame pose_desi_
Definition: cartesian_pose_controller.h:109
control_toolbox::Pid
tf
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
cartesian_pose_controller.h
ros::Duration
controller::CartesianPoseController::last_time_
ros::Time last_time_
Definition: cartesian_pose_controller.h:120
controller::CartesianPoseController::command
void command(const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
Definition: cartesian_pose_controller.cpp:205
pr2_mechanism_model::Chain::init
bool init(RobotState *robot_state, const std::string &root, const std::string &tip)
ros::NodeHandle
controller::CartesianPoseController::node_
ros::NodeHandle node_
Definition: cartesian_pose_controller.h:118
ros::Time::now
static Time now()
controller::CartesianPoseController::getPose
KDL::Frame getPose()
Definition: cartesian_pose_controller.cpp:193


robot_mechanism_controllers
Author(s): John Hsu, Melonee Wise, Stuart Glaser
autogenerated on Sat Nov 12 2022 03:33:22