kinematic_extension_urdf.h
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 #ifndef COB_TWIST_CONTROLLER_KINEMATIC_EXTENSIONS_KINEMATIC_EXTENSION_URDF_H
19 #define COB_TWIST_CONTROLLER_KINEMATIC_EXTENSIONS_KINEMATIC_EXTENSION_URDF_H
20 
21 #include <string>
22 #include <vector>
23 #include <ros/ros.h>
24 #include <std_msgs/Float64MultiArray.h>
25 #include <sensor_msgs/JointState.h>
26 
27 #include <urdf/model.h>
29 #include <Eigen/Geometry>
30 
32 
33 /* BEGIN KinematicExtensionURDF ****************************************************************************************/
36 {
37  public:
39  : KinematicExtensionBase(params)
40  {}
41 
43 
44  bool initExtension();
45  virtual KDL::Jacobian adjustJacobian(const KDL::Jacobian& jac_chain);
46  virtual JointStates adjustJointStates(const JointStates& joint_states);
47  virtual LimiterParams adjustLimiterParams(const LimiterParams& limiter_params);
48  virtual void processResultExtension(const KDL::JntArray& q_dot_ik);
49 
50  void jointstateCallback(const sensor_msgs::JointState::ConstPtr& msg);
51 
52  protected:
55 
56  std::string ext_base_;
57  std::string ext_tip_;
59  unsigned int ext_dof_;
60  std::vector<std::string> joint_names_;
62  std::vector<double> limits_max_;
63  std::vector<double> limits_min_;
64  std::vector<double> limits_vel_;
65  std::vector<double> limits_acc_;
66 };
67 /* END KinematicExtensionURDF **********************************************************************************************/
68 
69 
70 /* BEGIN KinematicExtensionTorso ****************************************************************************************/
73 {
74  public:
76  : KinematicExtensionURDF(params)
77  {}
78 
80 
82  {
83  ext_base_ = "torso_base_link";
86  {
87  return false;
88  }
89  else
90  {
91  joint_state_sub_ = nh_.subscribe("/torso/joint_states", 1, &KinematicExtensionURDF::jointstateCallback, dynamic_cast<KinematicExtensionURDF*>(this));
92  command_pub_ = nh_.advertise<std_msgs::Float64MultiArray>("/torso/joint_group_velocity_controller/command", 1);
93  return true;
94  }
95  }
96 };
97 /* END KinematicExtensionTorso **********************************************************************************************/
98 
99 #endif // COB_TWIST_CONTROLLER_KINEMATIC_EXTENSIONS_KINEMATIC_EXTENSION_URDF_H
msg
virtual KDL::Jacobian adjustJacobian(const KDL::Jacobian &jac_chain)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
virtual JointStates adjustJointStates(const JointStates &joint_states)
std::vector< std::string > joint_names_
void jointstateCallback(const sensor_msgs::JointState::ConstPtr &msg)
Abstract Helper Class to be used for Cartesian KinematicExtensions based on URDF. ...
virtual void processResultExtension(const KDL::JntArray &q_dot_ik)
Base class for kinematic extensions.
std::vector< double > limits_min_
const TwistControllerParams & params_
KinematicExtensionURDF(const TwistControllerParams &params)
KinematicExtensionTorso(const TwistControllerParams &params)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::vector< double > limits_max_
virtual LimiterParams adjustLimiterParams(const LimiterParams &limiter_params)
std::vector< double > limits_acc_
std::vector< double > limits_vel_
Class implementing a KinematicExtension for Torso based on URDF.


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Thu Apr 8 2021 02:40:00