cob_frame_tracker.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_FRAME_TRACKER_H
19 #define COB_FRAME_TRACKER_H
20 
21 #include <string>
22 #include <vector>
23 #include <math.h>
24 #include <algorithm>
25 #include <ros/ros.h>
26 
27 #include <std_msgs/String.h>
28 #include <std_msgs/Float64.h>
29 #include <std_msgs/Float64MultiArray.h>
30 #include <sensor_msgs/JointState.h>
31 #include <geometry_msgs/Twist.h>
32 #include <std_srvs/Trigger.h>
33 #include <cob_srvs/SetString.h>
34 
36 #include <cob_frame_tracker/FrameTrackerConfig.h>
37 #include <cob_frame_tracker/FrameTrackingAction.h>
38 
39 #include <tf/transform_listener.h>
40 #include <tf/transform_datatypes.h>
41 
43 #include <kdl/chainiksolvervel_pinv.hpp>
44 #include <kdl/chainfksolvervel_recursive.hpp>
45 #include <kdl/frames.hpp>
46 #include <kdl/jntarray.hpp>
47 #include <kdl/jntarrayvel.hpp>
48 
49 #include <control_toolbox/pid.h>
50 #include <dynamic_reconfigure/server.h>
51 #include <dynamic_reconfigure/Reconfigure.h>
52 #include <boost/thread/mutex.hpp>
53 
54 
56 
57 struct HoldTf
58 {
60  bool hold;
61 };
62 
63 
65 {
66 public:
68  {
69  ht_.hold = false;
70  }
71 
73  {
74  jntToCartSolver_vel_.reset();
75  as_.reset();
76  reconfigure_server_.reset();
77  }
78 
79  bool initialize();
80  void run(const ros::TimerEvent& event);
81 
82  void jointstateCallback(const sensor_msgs::JointState::ConstPtr& msg);
83 
84  bool startTrackingCallback(cob_srvs::SetString::Request& request, cob_srvs::SetString::Response& response);
85  bool startLookatCallback(cob_srvs::SetString::Request& request, cob_srvs::SetString::Response& response);
86  bool stopCallback(std_srvs::Trigger::Request& request, std_srvs::Trigger::Response& response);
87 
88  bool getTransform(const std::string& from, const std::string& to, tf::StampedTransform& stamped_tf);
89 
90  void publishZeroTwist();
91  void publishTwist(ros::Duration period, bool do_publish = true);
92  void publishHoldTwist(const ros::Duration& period);
93 
95  void goalCB();
96  void preemptCB();
97  void action_success();
98  void action_abort();
99 
100 private:
102 
103  double update_rate_;
105 
106  bool tracking_;
108  bool lookat_;
109  std::string chain_base_link_;
110  std::string chain_tip_link_;
111  std::string lookat_focus_frame_;
112  std::string tracking_frame_; // the frame tracking the target (i.e. chain_tip or lookat_focus)
113  std::string target_frame_; // the frame to be tracked
114 
115  double max_vel_lin_;
116  double max_vel_rot_;
117 
118  std::vector<std::string> joints_;
119  unsigned int dof_;
120 
123 
127 
131 
133  KDL::Chain chain_;
134  KDL::JntArray last_q_;
135  KDL::JntArray last_q_dot_;
137 
139 
143 
148 
150  std::string action_name_;
152 
153  cob_frame_tracker::FrameTrackingFeedback action_feedback_;
154  cob_frame_tracker::FrameTrackingResult action_result_;
155 
156  boost::recursive_mutex reconfig_mutex_;
158  void reconfigureCallback(cob_frame_tracker::FrameTrackerConfig& config, uint32_t level);
159 
161  int checkStatus();
162  bool checkInfinitesimalTwist(const KDL::Twist current);
163  bool checkCartDistanceViolation(const double dist, const double rot);
164  bool checkTwistViolation(const KDL::Twist current, const KDL::Twist target);
165 
167 
171 
179 
180  KDL::Twist current_twist_;
181  KDL::Twist target_twist_;
182 
185 
186  unsigned int abortion_counter_;
187  unsigned int max_abortions_;
188 };
189 
190 #endif
CobFrameTracker::ht_
HoldTf ht_
Definition: cob_frame_tracker.h:101
CobFrameTracker::reconfig_mutex_
boost::recursive_mutex reconfig_mutex_
Definition: cob_frame_tracker.h:156
CobFrameTracker::jointstate_sub_
ros::Subscriber jointstate_sub_
Definition: cob_frame_tracker.h:140
CobFrameTracker::tracking_start_time_
ros::Time tracking_start_time_
Definition: cob_frame_tracker.h:170
CobFrameTracker::startTrackingCallback
bool startTrackingCallback(cob_srvs::SetString::Request &request, cob_srvs::SetString::Response &response)
Definition: cob_frame_tracker.cpp:390
ros::Publisher
CobFrameTracker::twist_dead_threshold_rot_
double twist_dead_threshold_rot_
Definition: cob_frame_tracker.h:176
CobFrameTracker::max_vel_rot_
double max_vel_rot_
Definition: cob_frame_tracker.h:116
CobFrameTracker::startLookatCallback
bool startLookatCallback(cob_srvs::SetString::Request &request, cob_srvs::SetString::Response &response)
Definition: cob_frame_tracker.cpp:440
CobFrameTracker::lookat_focus_frame_
std::string lookat_focus_frame_
Definition: cob_frame_tracker.h:111
boost::shared_ptr< KDL::ChainFkSolverVel_recursive >
CobFrameTracker::initialize
bool initialize()
Definition: cob_frame_tracker.cpp:35
CobFrameTracker::stopCallback
bool stopCallback(std_srvs::Trigger::Request &request, std_srvs::Trigger::Response &response)
Definition: cob_frame_tracker.cpp:529
CobFrameTracker::action_name_
std::string action_name_
Action interface.
Definition: cob_frame_tracker.h:150
HoldTf::transform_tf
tf::StampedTransform transform_tf
Definition: cob_frame_tracker.h:59
CobFrameTracker::tracking_duration_
double tracking_duration_
Definition: cob_frame_tracker.h:169
ros.h
CobFrameTracker::tracking_
bool tracking_
Definition: cob_frame_tracker.h:106
CobFrameTracker::pid_controller_rot_z_
control_toolbox::Pid pid_controller_rot_z_
Definition: cob_frame_tracker.h:130
CobFrameTracker::checkTwistViolation
bool checkTwistViolation(const KDL::Twist current, const KDL::Twist target)
Definition: cob_frame_tracker.cpp:833
CobFrameTracker::abortion_counter_
unsigned int abortion_counter_
Definition: cob_frame_tracker.h:186
CobFrameTracker::action_success
void action_success()
Definition: cob_frame_tracker.cpp:625
CobFrameTracker::getTransform
bool getTransform(const std::string &from, const std::string &to, tf::StampedTransform &stamped_tf)
Definition: cob_frame_tracker.cpp:215
simple_action_server.h
CobFrameTracker::checkInfinitesimalTwist
bool checkInfinitesimalTwist(const KDL::Twist current)
Definition: cob_frame_tracker.cpp:785
CobFrameTracker::checkServiceCallStatus
int checkServiceCallStatus()
Definition: cob_frame_tracker.cpp:702
tf::StampedTransform
CobFrameTracker::cart_min_dist_threshold_rot_
double cart_min_dist_threshold_rot_
Definition: cob_frame_tracker.h:174
CobFrameTracker::twist_deviation_threshold_rot_
double twist_deviation_threshold_rot_
Definition: cob_frame_tracker.h:178
CobFrameTracker::cart_distance_
double cart_distance_
Definition: cob_frame_tracker.h:183
ros::ServiceServer
CobFrameTracker::lookat_
bool lookat_
Definition: cob_frame_tracker.h:108
CobFrameTracker::joints_
std::vector< std::string > joints_
Definition: cob_frame_tracker.h:118
CobFrameTracker::target_twist_
KDL::Twist target_twist_
Definition: cob_frame_tracker.h:181
CobFrameTracker::action_abort
void action_abort()
Definition: cob_frame_tracker.cpp:639
CobFrameTracker::~CobFrameTracker
~CobFrameTracker()
Definition: cob_frame_tracker.h:72
SAS_FrameTrackingAction_t
actionlib::SimpleActionServer< cob_frame_tracker::FrameTrackingAction > SAS_FrameTrackingAction_t
Definition: cob_frame_tracker.h:55
CobFrameTracker::publishZeroTwist
void publishZeroTwist()
Definition: cob_frame_tracker.cpp:233
CobFrameTracker::preemptCB
void preemptCB()
Definition: cob_frame_tracker.cpp:610
CobFrameTracker::start_tracking_server_
ros::ServiceServer start_tracking_server_
Definition: cob_frame_tracker.h:144
CobFrameTracker::max_vel_lin_
double max_vel_lin_
Definition: cob_frame_tracker.h:115
CobFrameTracker::start_lookat_server_
ros::ServiceServer start_lookat_server_
Definition: cob_frame_tracker.h:145
CobFrameTracker::last_q_dot_
KDL::JntArray last_q_dot_
Definition: cob_frame_tracker.h:135
CobFrameTracker::pid_controller_trans_z_
control_toolbox::Pid pid_controller_trans_z_
Definition: cob_frame_tracker.h:126
CobFrameTracker::current_twist_
KDL::Twist current_twist_
Definition: cob_frame_tracker.h:180
ros::ServiceClient
CobFrameTracker::last_q_
KDL::JntArray last_q_
Definition: cob_frame_tracker.h:134
CobFrameTracker::twist_dead_threshold_lin_
double twist_dead_threshold_lin_
Definition: cob_frame_tracker.h:175
CobFrameTracker::CobFrameTracker
CobFrameTracker()
Definition: cob_frame_tracker.h:67
ros::TimerEvent
CobFrameTracker::dof_
unsigned int dof_
Definition: cob_frame_tracker.h:119
CobFrameTracker::chain_base_link_
std::string chain_base_link_
Definition: cob_frame_tracker.h:109
CobFrameTracker::error_pub_
ros::Publisher error_pub_
Definition: cob_frame_tracker.h:142
CobFrameTracker::twist_deviation_threshold_lin_
double twist_deviation_threshold_lin_
Definition: cob_frame_tracker.h:177
CobFrameTracker::tracking_goal_
bool tracking_goal_
Definition: cob_frame_tracker.h:107
CobFrameTracker::movable_trans_
bool movable_trans_
Definition: cob_frame_tracker.h:121
CobFrameTracker::action_result_
cob_frame_tracker::FrameTrackingResult action_result_
Definition: cob_frame_tracker.h:154
kdl_parser.hpp
CobFrameTracker
Definition: cob_frame_tracker.h:64
CobFrameTracker::pid_controller_trans_x_
control_toolbox::Pid pid_controller_trans_x_
Definition: cob_frame_tracker.h:124
CobFrameTracker::tf_listener_
tf::TransformListener tf_listener_
Definition: cob_frame_tracker.h:138
transform_listener.h
CobFrameTracker::chain_
KDL::Chain chain_
KDL Conversion.
Definition: cob_frame_tracker.h:133
CobFrameTracker::tracking_frame_
std::string tracking_frame_
Definition: cob_frame_tracker.h:112
CobFrameTracker::stop_server_
ros::ServiceServer stop_server_
Definition: cob_frame_tracker.h:146
CobFrameTracker::jointstateCallback
void jointstateCallback(const sensor_msgs::JointState::ConstPtr &msg)
Definition: cob_frame_tracker.cpp:733
CobFrameTracker::update_rate_
double update_rate_
Definition: cob_frame_tracker.h:103
CobFrameTracker::run
void run(const ros::TimerEvent &event)
Definition: cob_frame_tracker.cpp:176
CobFrameTracker::publishHoldTwist
void publishHoldTwist(const ros::Duration &period)
Definition: cob_frame_tracker.cpp:338
transform_datatypes.h
CobFrameTracker::jntToCartSolver_vel_
boost::shared_ptr< KDL::ChainFkSolverVel_recursive > jntToCartSolver_vel_
Definition: cob_frame_tracker.h:136
CobFrameTracker::goalCB
void goalCB()
Action interface.
Definition: cob_frame_tracker.cpp:579
ros::Time
CobFrameTracker::reconfigure_server_
boost::shared_ptr< dynamic_reconfigure::Server< cob_frame_tracker::FrameTrackerConfig > > reconfigure_server_
Definition: cob_frame_tracker.h:157
CobFrameTracker::action_feedback_
cob_frame_tracker::FrameTrackingFeedback action_feedback_
Definition: cob_frame_tracker.h:153
HoldTf
Definition: cob_frame_tracker.h:57
actionlib::SimpleActionServer
CobFrameTracker::cart_min_dist_threshold_lin_
double cart_min_dist_threshold_lin_
Definition: cob_frame_tracker.h:173
CobFrameTracker::checkCartDistanceViolation
bool checkCartDistanceViolation(const double dist, const double rot)
Definition: cob_frame_tracker.cpp:817
CobFrameTracker::stop_on_goal_
bool stop_on_goal_
Definition: cob_frame_tracker.h:168
CobFrameTracker::twist_pub_
ros::Publisher twist_pub_
Definition: cob_frame_tracker.h:141
CobFrameTracker::movable_rot_
bool movable_rot_
Definition: cob_frame_tracker.h:122
tf::TransformListener
control_toolbox::Pid
CobFrameTracker::pid_controller_rot_y_
control_toolbox::Pid pid_controller_rot_y_
Definition: cob_frame_tracker.h:129
CobFrameTracker::pid_controller_rot_x_
control_toolbox::Pid pid_controller_rot_x_
Definition: cob_frame_tracker.h:128
CobFrameTracker::checkStatus
int checkStatus()
ABORTION CRITERIA:
Definition: cob_frame_tracker.cpp:653
CobFrameTracker::timer_
ros::Timer timer_
Definition: cob_frame_tracker.h:104
CobFrameTracker::chain_tip_link_
std::string chain_tip_link_
Definition: cob_frame_tracker.h:110
pid.h
CobFrameTracker::publishTwist
void publishTwist(ros::Duration period, bool do_publish=true)
Definition: cob_frame_tracker.cpp:243
CobFrameTracker::rot_distance_
double rot_distance_
Definition: cob_frame_tracker.h:184
CobFrameTracker::reconfigureCallback
void reconfigureCallback(cob_frame_tracker::FrameTrackerConfig &config, uint32_t level)
Definition: cob_frame_tracker.cpp:773
CobFrameTracker::reconfigure_client_
ros::ServiceClient reconfigure_client_
Definition: cob_frame_tracker.h:147
CobFrameTracker::enable_abortion_checking_
bool enable_abortion_checking_
Definition: cob_frame_tracker.h:172
CobFrameTracker::target_frame_
std::string target_frame_
Definition: cob_frame_tracker.h:113
CobFrameTracker::max_abortions_
unsigned int max_abortions_
Definition: cob_frame_tracker.h:187
ros::Duration
CobFrameTracker::as_
boost::shared_ptr< SAS_FrameTrackingAction_t > as_
Definition: cob_frame_tracker.h:151
ros::Timer
CobFrameTracker::pid_controller_trans_y_
control_toolbox::Pid pid_controller_trans_y_
Definition: cob_frame_tracker.h:125
HoldTf::hold
bool hold
Definition: cob_frame_tracker.h:60
ros::Subscriber


cob_frame_tracker
Author(s): Felix Messmer
autogenerated on Mon May 1 2023 02:44:25