kinematic_extension_lookat.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #include <string>
19 #include <vector>
20 #include <limits>
21 #include <algorithm>
22 #include <tf_conversions/tf_kdl.h>
25 
26 /* BEGIN KinematicExtensionLookat ********************************************************************************************/
28 {
30  KDL::Tree tree;
31  if (!kdl_parser::treeFromParam("robot_description", tree))
32  {
33  ROS_ERROR("Failed to construct kdl tree");
34  return false;
35  }
36 
37  KDL::Chain chain_main;
38  tree.getChain(params_.chain_base_link, params_.chain_tip_link, chain_main);
39  if (chain_main.getNrOfJoints() == 0)
40  {
41  ROS_ERROR("Failed to initialize kinematic chain");
42  return false;
43  }
44 
45  KDL::Joint::JointType lookat_lin_joint_type = KDL::Joint::None;
47  {
48  case X_POSITIVE:
49  lookat_lin_joint_type = KDL::Joint::TransX;
50  break;
51  case Y_POSITIVE:
52  lookat_lin_joint_type = KDL::Joint::TransY;
53  break;
54  case Z_POSITIVE:
55  lookat_lin_joint_type = KDL::Joint::TransZ;
56  break;
57  case X_NEGATIVE:
58  lookat_lin_joint_type = KDL::Joint::TransX;
59  ROS_ERROR("X_NEGATIVE axis_type not supported");
60  return false;
61  case Y_NEGATIVE:
62  lookat_lin_joint_type = KDL::Joint::TransY;
63  ROS_ERROR("Y_NEGATIVE axis_type not supported");
64  return false;
65  case Z_NEGATIVE:
66  lookat_lin_joint_type = KDL::Joint::TransZ;
67  ROS_ERROR("Z_NEGATIVE axis_type not supported");
68  return false;
69  default:
70  ROS_ERROR("LookatAxisType %d not defined! Using default: 'X_POSITIVE'!", params_.lookat_offset.lookat_axis_type);
71  lookat_lin_joint_type = KDL::Joint::TransX;
72  break;
73  }
74 
75  KDL::Frame offset;
76  try
77  {
78  tf::StampedTransform offset_transform;
80  tf::transformTFToKDL(offset_transform, offset);
81  }
82  catch (tf::TransformException& ex)
83  {
84  ROS_ERROR("LookatAction: %s", ex.what());
85  ROS_WARN_STREAM("Using 'lookat_offset' instead");
88  }
89 
90  //fixed pointing offset
91  KDL::Joint offset_joint("offset_joint", KDL::Joint::None);
92  KDL::Segment offset_link("offset_link", offset_joint, offset);
93  chain_ext_.addSegment(offset_link);
94 
95  //lookat chain
96  KDL::Joint lookat_lin_joint("lookat_lin_joint", lookat_lin_joint_type);
97  KDL::Segment lookat_rotx_link("lookat_rotx_link", lookat_lin_joint);
98  chain_ext_.addSegment(lookat_rotx_link);
99  limits_ext_max_.push_back(std::numeric_limits<double>::max());
100  limits_ext_min_.push_back(-std::numeric_limits<double>::max());
101  limits_ext_vel_.push_back(5.0);
102  limits_ext_acc_.push_back(std::numeric_limits<double>::max());
103 
104  KDL::Joint lookat_rotx_joint("lookat_rotx_joint", KDL::Joint::RotX);
105  KDL::Segment lookat_roty_link("lookat_roty_link", lookat_rotx_joint);
106  chain_ext_.addSegment(lookat_roty_link);
107  // limits_ext_max_.push_back(M_PI);
108  // limits_ext_min_.push_back(-M_PI);
109  limits_ext_max_.push_back(std::numeric_limits<double>::max());
110  limits_ext_min_.push_back(-std::numeric_limits<double>::max());
111  // limits_ext_vel_.push_back(std::numeric_limits<double>::max());
112  limits_ext_vel_.push_back(M_PI);
113  limits_ext_acc_.push_back(std::numeric_limits<double>::max());
114 
115  KDL::Joint lookat_roty_joint("lookat_roty_joint", KDL::Joint::RotY);
116  KDL::Segment lookat_rotz_link("lookat_rotz_link", lookat_roty_joint);
117  chain_ext_.addSegment(lookat_rotz_link);
118  // limits_ext_max_.push_back(M_PI);
119  // limits_ext_min_.push_back(-M_PI);
120  limits_ext_max_.push_back(std::numeric_limits<double>::max());
121  limits_ext_min_.push_back(-std::numeric_limits<double>::max());
122  // limits_ext_vel_.push_back(std::numeric_limits<double>::max());
123  limits_ext_vel_.push_back(M_PI);
124  limits_ext_acc_.push_back(std::numeric_limits<double>::max());
125 
126  KDL::Joint lookat_rotz_joint("lookat_rotz_joint", KDL::Joint::RotZ);
127  KDL::Segment lookat_focus_frame("lookat_focus_frame", lookat_rotz_joint);
128  chain_ext_.addSegment(lookat_focus_frame);
129  // limits_ext_max_.push_back(M_PI);
130  // limits_ext_min_.push_back(-M_PI);
131  limits_ext_max_.push_back(std::numeric_limits<double>::max());
132  limits_ext_min_.push_back(-std::numeric_limits<double>::max());
133  // limits_ext_vel_.push_back(std::numeric_limits<double>::max());
134  limits_ext_vel_.push_back(M_PI);
135  limits_ext_acc_.push_back(std::numeric_limits<double>::max());
136 
137  chain_full_ = chain_main;
138  chain_full_.addChain(chain_ext_);
139 
140  fk_solver_ext_.reset(new KDL::ChainFkSolverPos_recursive(chain_ext_));
141  jnt2jac_.reset(new KDL::ChainJntToJacSolver(chain_full_));
142 
143  this->ext_dof_ = 4;
144  this->joint_states_ext_.last_q_.resize(ext_dof_);
145  KDL::SetToZero(this->joint_states_ext_.last_q_);
146  this->joint_states_ext_.last_q_dot_.resize(ext_dof_);
147  KDL::SetToZero(this->joint_states_ext_.last_q_dot_);
148  this->joint_states_ext_.current_q_.resize(ext_dof_);
149  KDL::SetToZero(this->joint_states_ext_.current_q_);
151  KDL::SetToZero(this->joint_states_ext_.current_q_dot_);
152 
153  integrator_.reset(new SimpsonIntegrator(ext_dof_, 0.2)); // default smoothing: 0.2
154 
156  timer_.start();
157 
158  return true;
159 }
160 
161 KDL::Jacobian KinematicExtensionLookat::adjustJacobian(const KDL::Jacobian& jac_chain)
162 {
164  boost::mutex::scoped_lock lock(mutex_);
165  KDL::Jacobian jac_full(chain_full_.getNrOfJoints());
166 
167  jnt2jac_->JntToJac(joint_states_full_.current_q_ , jac_full);
168 
169  return jac_full;
170 }
171 
173 {
174  boost::mutex::scoped_lock lock(mutex_);
175  unsigned int chain_dof = joint_states.current_q_.rows();
176  joint_states_full_.current_q_.resize(chain_dof + ext_dof_);
177  joint_states_full_.last_q_.resize(chain_dof + ext_dof_);
178  joint_states_full_.current_q_dot_.resize(chain_dof + ext_dof_);
179  joint_states_full_.last_q_dot_.resize(chain_dof + ext_dof_);
180 
181  for (unsigned int i = 0; i< chain_dof; i++)
182  {
183  joint_states_full_.current_q_(i) = joint_states.current_q_(i);
184  joint_states_full_.last_q_(i) = joint_states.last_q_(i);
185  joint_states_full_.current_q_dot_(i) = joint_states.current_q_dot_(i);
186  joint_states_full_.last_q_dot_(i) = joint_states.last_q_dot_(i);
187  }
188  for (unsigned int i = 0; i < ext_dof_; i++)
189  {
190  joint_states_full_.current_q_(chain_dof + i) = this->joint_states_ext_.current_q_(i);
191  joint_states_full_.last_q_(chain_dof + i) = this->joint_states_ext_.last_q_(i);
194  }
195 
196  return joint_states_full_;
197 }
198 
200 {
201  LimiterParams lp = limiter_params;
202  for (unsigned int i = 0; i < ext_dof_; i++)
203  {
204  lp.limits_max.push_back(limits_ext_max_[i]);
205  lp.limits_min.push_back(limits_ext_min_[i]);
206  lp.limits_vel.push_back(limits_ext_vel_[i]);
207  lp.limits_acc.push_back(limits_ext_acc_[i]);
208  }
209  return lp;
210 }
211 
212 void KinematicExtensionLookat::processResultExtension(const KDL::JntArray& q_dot_ik)
213 {
215  boost::mutex::scoped_lock lock(mutex_);
216  std::vector<double> pos;
217  std::vector<double> vel;
218 
219  for (unsigned int i = 0; i < ext_dof_; i++)
220  {
221  joint_states_ext_.current_q_dot_(i) = q_dot_ik(params_.dof + i);
222  }
223 
224  if (integrator_->updateIntegration(joint_states_ext_.current_q_dot_, joint_states_ext_.current_q_, pos, vel))
225  {
226  for (unsigned int i = 0; i < ext_dof_; i++)
227  {
230  joint_states_ext_.current_q_(i) = std::max(pos[i], 0.1); // do not look backwards
231  joint_states_ext_.current_q_dot_(i) = vel[i];
232  }
233  }
234 }
235 
237 {
238  boost::mutex::scoped_lock lock(mutex_);
239  KDL::Frame focus_frame;
240 
241  fk_solver_ext_->JntToCart(joint_states_ext_.current_q_, focus_frame);
242 
243  tf::Transform transform;
244  tf::transformKDLToTF(focus_frame, transform);
245  br_.sendTransform(tf::StampedTransform(transform, ros::Time::now(), params_.chain_tip_link, "lookat_focus_frame"));
246 }
247 
248 /* END KinematicExtensionLookat ********************************************************************************************/
KinematicExtensionLookat::adjustLimiterParams
virtual LimiterParams adjustLimiterParams(const LimiterParams &limiter_params)
Definition: kinematic_extension_lookat.cpp:199
LookatOffset::lookat_axis_type
LookatAxisTypes lookat_axis_type
Definition: cob_twist_controller_data_types.h:102
JointStates::last_q_dot_
KDL::JntArray last_q_dot_
Definition: cob_twist_controller_data_types.h:117
Y_NEGATIVE
@ Y_NEGATIVE
Definition: cob_twist_controller_data_types.h:85
KinematicExtensionLookat::timer_
ros::Timer timer_
Definition: kinematic_extension_lookat.h:72
KinematicExtensionBase::nh_
ros::NodeHandle nh_
Definition: kinematic_extension_base.h:47
LimiterParams::limits_min
std::vector< double > limits_min
Definition: cob_twist_controller_data_types.h:189
KinematicExtensionLookat::limits_ext_vel_
std::vector< double > limits_ext_vel_
Definition: kinematic_extension_lookat.h:63
TwistControllerParams::lookat_offset
LookatOffset lookat_offset
Definition: cob_twist_controller_data_types.h:285
tf::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
KinematicExtensionLookat::adjustJacobian
virtual KDL::Jacobian adjustJacobian(const KDL::Jacobian &jac_chain)
Definition: kinematic_extension_lookat.cpp:161
LookatOffset::translation_z
double translation_z
Definition: cob_twist_controller_data_types.h:105
KinematicExtensionBase::tf_listener_
tf::TransformListener tf_listener_
Definition: kinematic_extension_base.h:48
KinematicExtensionLookat::mutex_
boost::mutex mutex_
Definition: kinematic_extension_lookat.h:71
KinematicExtensionLookat::broadcastFocusFrame
void broadcastFocusFrame(const ros::TimerEvent &event)
Definition: kinematic_extension_lookat.cpp:236
JointStates::last_q_
KDL::JntArray last_q_
Definition: cob_twist_controller_data_types.h:115
LimiterParams::limits_acc
std::vector< double > limits_acc
Definition: cob_twist_controller_data_types.h:191
TwistControllerParams::dof
uint8_t dof
Definition: cob_twist_controller_data_types.h:255
JointStates::current_q_dot_
KDL::JntArray current_q_dot_
Definition: cob_twist_controller_data_types.h:116
LookatOffset::rotation_z
double rotation_z
Definition: cob_twist_controller_data_types.h:108
tf::transformTFToKDL
void transformTFToKDL(const tf::Transform &t, KDL::Frame &k)
LookatOffset::rotation_y
double rotation_y
Definition: cob_twist_controller_data_types.h:107
KinematicExtensionLookat::chain_ext_
KDL::Chain chain_ext_
Definition: kinematic_extension_lookat.h:57
Z_POSITIVE
@ Z_POSITIVE
Definition: cob_twist_controller_data_types.h:83
SimpsonIntegrator
Definition: simpson_integrator.h:29
KinematicExtensionLookat::br_
tf::TransformBroadcaster br_
Definition: kinematic_extension_lookat.h:73
tf::StampedTransform
KinematicExtensionLookat::initExtension
bool initExtension()
Definition: kinematic_extension_lookat.cpp:27
LookatOffset::rotation_x
double rotation_x
Definition: cob_twist_controller_data_types.h:106
KinematicExtensionLookat::limits_ext_min_
std::vector< double > limits_ext_min_
Definition: kinematic_extension_lookat.h:62
KinematicExtensionLookat::ext_dof_
unsigned int ext_dof_
Definition: kinematic_extension_lookat.h:56
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
tree
tree
tf::transformKDLToTF
void transformKDLToTF(const KDL::Frame &k, tf::Transform &t)
KinematicExtensionBase::params_
const TwistControllerParams & params_
Definition: kinematic_extension_base.h:49
KinematicExtensionLookat::limits_ext_acc_
std::vector< double > limits_ext_acc_
Definition: kinematic_extension_lookat.h:64
X_NEGATIVE
@ X_NEGATIVE
Definition: cob_twist_controller_data_types.h:84
KinematicExtensionLookat::jnt2jac_
boost::shared_ptr< KDL::ChainJntToJacSolver > jnt2jac_
Definition: kinematic_extension_lookat.h:66
kinematic_extension_lookat.h
LimiterParams::limits_vel
std::vector< double > limits_vel
Definition: cob_twist_controller_data_types.h:190
ROS_ERROR
#define ROS_ERROR(...)
kdl_parser::treeFromParam
KDL_PARSER_PUBLIC bool treeFromParam(const std::string &param, KDL::Tree &tree)
KinematicExtensionLookat::processResultExtension
virtual void processResultExtension(const KDL::JntArray &q_dot_ik)
Definition: kinematic_extension_lookat.cpp:212
Y_POSITIVE
@ Y_POSITIVE
Definition: cob_twist_controller_data_types.h:82
TwistControllerParams::lookat_pointing_frame
std::string lookat_pointing_frame
Definition: cob_twist_controller_data_types.h:284
ros::TimerEvent
tf::Transform
KinematicExtensionLookat::chain_full_
KDL::Chain chain_full_
Definition: kinematic_extension_lookat.h:58
LimiterParams
Definition: cob_twist_controller_data_types.h:162
KinematicExtensionLookat::integrator_
boost::shared_ptr< SimpsonIntegrator > integrator_
Definition: kinematic_extension_lookat.h:69
X_POSITIVE
@ X_POSITIVE
Definition: cob_twist_controller_data_types.h:81
KinematicExtensionLookat::fk_solver_ext_
boost::shared_ptr< KDL::ChainFkSolverPos_recursive > fk_solver_ext_
Definition: kinematic_extension_lookat.h:67
ros::Time
LookatOffset::rotation_w
double rotation_w
Definition: cob_twist_controller_data_types.h:109
tf_kdl.h
Z_NEGATIVE
@ Z_NEGATIVE
Definition: cob_twist_controller_data_types.h:86
KinematicExtensionLookat::limits_ext_max_
std::vector< double > limits_ext_max_
Definition: kinematic_extension_lookat.h:61
TwistControllerParams::chain_tip_link
std::string chain_tip_link
Definition: cob_twist_controller_data_types.h:257
LimiterParams::limits_max
std::vector< double > limits_max
Definition: cob_twist_controller_data_types.h:188
JointStates
Definition: cob_twist_controller_data_types.h:112
eigen_kdl.h
JointStates::current_q_
KDL::JntArray current_q_
Definition: cob_twist_controller_data_types.h:114
tf::Transformer::lookupTransform
void lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, StampedTransform &transform) const
ros::Timer::start
void start()
TwistControllerParams::chain_base_link
std::string chain_base_link
Definition: cob_twist_controller_data_types.h:256
tf2::TransformException
KinematicExtensionLookat::joint_states_ext_
JointStates joint_states_ext_
Definition: kinematic_extension_lookat.h:59
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
LookatOffset::translation_x
double translation_x
Definition: cob_twist_controller_data_types.h:103
KinematicExtensionLookat::joint_states_full_
JointStates joint_states_full_
Definition: kinematic_extension_lookat.h:60
ros::Time::now
static Time now()
KinematicExtensionLookat::adjustJointStates
virtual JointStates adjustJointStates(const JointStates &joint_states)
Definition: kinematic_extension_lookat.cpp:172
LookatOffset::translation_y
double translation_y
Definition: cob_twist_controller_data_types.h:104


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Mon May 1 2023 02:44:43