cob_frame_tracker.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 
00018 #include <string>
00019 #include <algorithm>
00020 #include <math.h>
00021 #include <ros/ros.h>
00022 
00023 #include <geometry_msgs/Twist.h>
00024 #include <sensor_msgs/JointState.h>
00025 #include <cob_frame_tracker/cob_frame_tracker.h>
00026 #include <cob_frame_tracker/FrameTrackingAction.h>
00027 
00028 #include <kdl_parser/kdl_parser.hpp>
00029 #include <kdl/chainiksolvervel_pinv.hpp>
00030 #include <kdl/chainfksolvervel_recursive.hpp>
00031 #include <kdl/jntarray.hpp>
00032 #include <kdl/jntarrayvel.hpp>
00033 
00034 
00035 bool CobFrameTracker::initialize()
00036 {
00037     ros::NodeHandle nh_;
00038     ros::NodeHandle nh_tracker("frame_tracker");
00039     ros::NodeHandle nh_twist("twist_controller");
00040 
00042     if (nh_tracker.hasParam("update_rate"))
00043     {    nh_tracker.getParam("update_rate", update_rate_);    }
00044     else
00045     {    update_rate_ = 50.0;    }    // hz
00046 
00047     if (nh_.hasParam("chain_base_link"))
00048     {
00049         nh_.getParam("chain_base_link", chain_base_link_);
00050     }
00051     else
00052     {
00053         ROS_ERROR("No chain_base_link specified. Aborting!");
00054         return false;
00055     }
00056 
00057     if (nh_.hasParam("chain_tip_link"))
00058     {
00059         nh_.getParam("chain_tip_link", chain_tip_link_);
00060     }
00061     else
00062     {
00063         ROS_ERROR("No chain_tip_link specified. Aborting!");
00064         return false;
00065     }
00066 
00067     if (!nh_.getParam("joint_names", joints_))
00068     {
00069         ROS_ERROR("Parameter 'joint_names' not set");
00070         return false;
00071     }
00072 
00073     KDL::Tree tree;
00074     if (!kdl_parser::treeFromParam("/robot_description", tree))
00075     {
00076         ROS_ERROR("Failed to construct kdl tree");
00077         return false;
00078     }
00079 
00080     tree.getChain(chain_base_link_, chain_tip_link_, chain_);
00081     if (chain_.getNrOfJoints() == 0)
00082     {
00083         ROS_ERROR("Failed to initialize kinematic chain");
00084         return false;
00085     }
00086 
00087     // initialize variables and current joint values and velocities
00088     dof_ = chain_.getNrOfJoints();
00089     last_q_ = KDL::JntArray(dof_);
00090     last_q_dot_ = KDL::JntArray(dof_);
00091 
00092     if (nh_tracker.hasParam("movable_trans"))
00093     {    nh_tracker.getParam("movable_trans", movable_trans_);    }
00094     else
00095     {    movable_trans_ = true;    }
00096     if (nh_tracker.hasParam("movable_rot"))
00097     {    nh_tracker.getParam("movable_rot", movable_rot_);    }
00098     else
00099     {    movable_rot_ = true;    }
00100 
00101     if (nh_tracker.hasParam("max_vel_lin"))
00102     {    nh_tracker.getParam("max_vel_lin", max_vel_lin_);    }
00103     else
00104     {    max_vel_lin_ = 0.1;    }    // m/sec
00105 
00106     if (nh_tracker.hasParam("max_vel_rot"))
00107     {    nh_tracker.getParam("max_vel_rot", max_vel_rot_);    }
00108     else
00109     {    max_vel_rot_ = 0.1;    }    // rad/sec
00110 
00111     // Load PID Controller using gains set on parameter server
00112     pid_controller_trans_x_.init(ros::NodeHandle(nh_tracker, "pid_trans_x"));
00113     pid_controller_trans_x_.reset();
00114     pid_controller_trans_y_.init(ros::NodeHandle(nh_tracker, "pid_trans_y"));
00115     pid_controller_trans_y_.reset();
00116     pid_controller_trans_z_.init(ros::NodeHandle(nh_tracker, "pid_trans_z"));
00117     pid_controller_trans_z_.reset();
00118 
00119     pid_controller_rot_x_.init(ros::NodeHandle(nh_tracker, "pid_rot_x"));
00120     pid_controller_rot_x_.reset();
00121     pid_controller_rot_y_.init(ros::NodeHandle(nh_tracker, "pid_rot_y"));
00122     pid_controller_rot_y_.reset();
00123     pid_controller_rot_z_.init(ros::NodeHandle(nh_tracker, "pid_rot_z"));
00124     pid_controller_rot_z_.reset();
00125 
00126     tracking_ = false;
00127     tracking_goal_ = false;
00128     lookat_ = false;
00129     tracking_frame_ = chain_tip_link_;
00130     target_frame_ = chain_tip_link_;
00131     lookat_focus_frame_ = "lookat_focus_frame";
00132 
00133     // ABORTION CRITERIA:
00134     enable_abortion_checking_ = true;
00135     cart_min_dist_threshold_lin_ = 0.01;
00136     cart_min_dist_threshold_rot_ = 0.01;
00137     twist_dead_threshold_lin_ = 0.05;
00138     twist_dead_threshold_rot_ = 0.05;
00139     twist_deviation_threshold_lin_ = 0.5;
00140     twist_deviation_threshold_rot_ = 0.5;
00141 
00142     cart_distance_ = 0.0;
00143     rot_distance_ = 0.0;
00144 
00145     current_twist_.Zero();
00146     target_twist_.Zero();
00147 
00148     abortion_counter_ = 0;
00149     max_abortions_ = update_rate_;    // if tracking fails for 1 second
00150 
00151     reconfigure_server_.reset(new dynamic_reconfigure::Server<cob_frame_tracker::FrameTrackerConfig>(reconfig_mutex_, nh_tracker));
00152     reconfigure_server_->setCallback(boost::bind(&CobFrameTracker::reconfigureCallback,   this, _1, _2));
00153 
00154     reconfigure_client_ = nh_twist.serviceClient<dynamic_reconfigure::Reconfigure>("set_parameters");
00155 
00156     jointstate_sub_ = nh_.subscribe("joint_states", 1, &CobFrameTracker::jointstateCallback, this);
00157     twist_pub_ = nh_twist.advertise<geometry_msgs::TwistStamped> ("command_twist_stamped", 1);
00158     error_pub_ = nh_twist.advertise<geometry_msgs::TwistStamped> ("controller_errors", 1);
00159 
00160     start_tracking_server_ = nh_tracker.advertiseService("start_tracking", &CobFrameTracker::startTrackingCallback, this);
00161     start_lookat_server_ = nh_tracker.advertiseService("start_lookat", &CobFrameTracker::startLookatCallback, this);
00162     stop_server_ = nh_tracker.advertiseService("stop", &CobFrameTracker::stopCallback, this);
00163 
00164     action_name_ = "tracking_action";
00165     as_.reset(new SAS_FrameTrackingAction_t(nh_tracker, action_name_, false));
00166     as_->registerGoalCallback(boost::bind(&CobFrameTracker::goalCB, this));
00167     as_->registerPreemptCallback(boost::bind(&CobFrameTracker::preemptCB, this));
00168     as_->start();
00169 
00170     timer_ = nh_.createTimer(ros::Duration(1/update_rate_), &CobFrameTracker::run, this);
00171     timer_.start();
00172 
00173     return true;
00174 }
00175 
00176 void CobFrameTracker::run(const ros::TimerEvent& event)
00177 {
00178     ros::Duration period = event.current_real - event.last_real;
00179 
00180     if (tracking_ || tracking_goal_ || lookat_)
00181     {
00182         if (tracking_goal_)  // tracking on action goal.
00183         {
00184             int status = checkStatus();
00185 
00186             if (status > 0)
00187             {
00188                 action_success();
00189             }
00190             else if (status < 0)
00191             {
00192                 action_abort();
00193             }
00194             else
00195             {
00196                 // action still active - publish feedback
00197                 if (as_->isActive()) { as_->publishFeedback(action_feedback_); }
00198             }
00199         }
00200         else  // tracking/lookat on service call
00201         {
00202             int status = checkServiceCallStatus();
00203             if (status < 0)
00204             {
00205                 this->publishHoldTwist(period);
00206             }
00207 
00208             ht_.hold = abortion_counter_ >= max_abortions_;  // only for service call in case of action ht_.hold = false. What to do with actions?
00209         }
00210 
00211         publishTwist(period, !ht_.hold);  // if not publishing then just update data!
00212     }
00213 }
00214 
00215 bool CobFrameTracker::getTransform(const std::string& from, const std::string& to, tf::StampedTransform& stamped_tf)
00216 {
00217     bool transform = false;
00218 
00219     try
00220     {
00221         tf_listener_.waitForTransform(from, to, ros::Time(0), ros::Duration(0.2));
00222         tf_listener_.lookupTransform(from, to, ros::Time(0), stamped_tf);
00223         transform = true;
00224     }
00225     catch (tf::TransformException& ex)
00226     {
00227         ROS_ERROR("CobFrameTracker::getTransform: \n%s", ex.what());
00228     }
00229 
00230     return transform;
00231 }
00232 
00233 void CobFrameTracker::publishZeroTwist()
00234 {
00235     // publish zero Twist for stopping
00236     geometry_msgs::TwistStamped twist_msg;
00237     ros::Time now = ros::Time::now();
00238     twist_msg.header.frame_id = tracking_frame_;
00239     twist_msg.header.stamp = now;
00240     twist_pub_.publish(twist_msg);
00241 }
00242 
00243 void CobFrameTracker::publishTwist(ros::Duration period, bool do_publish)
00244 {
00245     tf::StampedTransform transform_tf;
00246     bool success = this->getTransform(tracking_frame_, target_frame_, transform_tf);
00247 
00248     geometry_msgs::TwistStamped twist_msg, error_msg;
00249     ros::Time now = ros::Time::now();
00250     twist_msg.header.frame_id = tracking_frame_;
00251     twist_msg.header.stamp = now;
00252     error_msg.header.frame_id = tracking_frame_;
00253     error_msg.header.stamp = now;
00254 
00255     if (!success)
00256     {
00257         ROS_WARN("publishTwist: failed to getTransform");
00258         return;
00259     }
00260 
00261     double error_trans_x = transform_tf.getOrigin().x();
00262     double error_trans_y = transform_tf.getOrigin().y();
00263     double error_trans_z = transform_tf.getOrigin().z();
00264     double error_rot_x = transform_tf.getRotation().x();
00265     double error_rot_y = transform_tf.getRotation().y();
00266     double error_rot_z = transform_tf.getRotation().z();
00267 
00268     error_msg.twist.linear.x = error_trans_x;
00269     error_msg.twist.linear.y = error_trans_y;
00270     error_msg.twist.linear.z = error_trans_z;
00271     error_msg.twist.angular.x = error_rot_x;
00272     error_msg.twist.angular.y = error_rot_y;
00273     error_msg.twist.angular.z = error_rot_z;
00274 
00275     if (movable_trans_)
00276     {
00277         twist_msg.twist.linear.x = pid_controller_trans_x_.computeCommand(error_trans_x, period);
00278         twist_msg.twist.linear.y = pid_controller_trans_y_.computeCommand(error_trans_y, period);
00279         twist_msg.twist.linear.z = pid_controller_trans_z_.computeCommand(error_trans_z, period);
00280     }
00281 
00282     if (movable_rot_)
00283     {
00286 
00287         twist_msg.twist.angular.x = pid_controller_rot_x_.computeCommand(error_rot_x, period);
00288         twist_msg.twist.angular.y = pid_controller_rot_y_.computeCommand(error_rot_y, period);
00289         twist_msg.twist.angular.z = pid_controller_rot_z_.computeCommand(error_rot_z, period);
00290     }
00291 
00293 
00315     // eukl distance
00316     cart_distance_ = sqrt(pow(transform_tf.getOrigin().x(), 2) + pow(transform_tf.getOrigin().y(), 2) + pow(transform_tf.getOrigin().z(), 2));
00317     rot_distance_ = sqrt(pow(transform_tf.getRotation().x(), 2) + pow(transform_tf.getRotation().y(), 2) + pow(transform_tf.getRotation().z(), 2));
00318 
00319     // rot distance
00320     // // TODO: change to cartesian rot
00321     // rot_distance_ = 2* acos(transform_msg.transform.rotation.w);
00322 
00323     // get target_twist
00324     target_twist_.vel.x(twist_msg.twist.linear.x);
00325     target_twist_.vel.y(twist_msg.twist.linear.y);
00326     target_twist_.vel.z(twist_msg.twist.linear.z);
00327     target_twist_.rot.x(twist_msg.twist.angular.x);
00328     target_twist_.rot.y(twist_msg.twist.angular.y);
00329     target_twist_.rot.z(twist_msg.twist.angular.z);
00330 
00331     if (do_publish)
00332     {
00333         twist_pub_.publish(twist_msg);
00334         error_pub_.publish(error_msg);
00335     }
00336 }
00337 
00338 void CobFrameTracker::publishHoldTwist(const ros::Duration& period)
00339 {
00340     tf::StampedTransform transform_tf;
00341     bool success = this->getTransform(chain_base_link_, tracking_frame_, transform_tf);
00342 
00343     geometry_msgs::TwistStamped twist_msg, error_msg;
00344     ros::Time now = ros::Time::now();
00345     twist_msg.header.frame_id = tracking_frame_;
00346     twist_msg.header.stamp = now;
00347     error_msg.header.frame_id = tracking_frame_;
00348     error_msg.header.stamp = now;
00349 
00350     if (!this->ht_.hold)
00351     {
00352         ROS_ERROR_STREAM_THROTTLE(1, "Abortion active: Publishing zero twist");
00353         ht_.hold = success;
00354         ht_.transform_tf = transform_tf;
00355     }
00356     else
00357     {
00358         if (success)
00359         {
00360             ROS_ERROR_STREAM_THROTTLE(1, "Abortion active: Publishing hold posture twist");
00361 
00362             double error_trans_x = ht_.transform_tf.getOrigin().x() - transform_tf.getOrigin().x();
00363             double error_trans_y = ht_.transform_tf.getOrigin().y() - transform_tf.getOrigin().y();
00364             double error_trans_z = ht_.transform_tf.getOrigin().z() - transform_tf.getOrigin().z();
00365             double error_rot_x = ht_.transform_tf.getRotation().x() - transform_tf.getRotation().x();
00366             double error_rot_y = ht_.transform_tf.getRotation().y() - transform_tf.getRotation().y();
00367             double error_rot_z = ht_.transform_tf.getRotation().z() - transform_tf.getRotation().z();
00368 
00369             error_msg.twist.linear.x = error_trans_x;
00370             error_msg.twist.linear.y = error_trans_y;
00371             error_msg.twist.linear.z = error_trans_z;
00372             error_msg.twist.angular.x = error_rot_x;
00373             error_msg.twist.angular.y = error_rot_y;
00374             error_msg.twist.angular.z = error_rot_z;
00375 
00376             twist_msg.twist.linear.x = pid_controller_trans_x_.computeCommand(error_trans_x, period);
00377             twist_msg.twist.linear.y = pid_controller_trans_y_.computeCommand(error_trans_y, period);
00378             twist_msg.twist.linear.z = pid_controller_trans_z_.computeCommand(error_trans_z, period);
00379 
00380             twist_msg.twist.angular.x = pid_controller_rot_x_.computeCommand(error_rot_x, period);
00381             twist_msg.twist.angular.y = pid_controller_rot_y_.computeCommand(error_rot_y, period);
00382             twist_msg.twist.angular.z = pid_controller_rot_z_.computeCommand(error_rot_z, period);
00383         }
00384     }
00385 
00386     twist_pub_.publish(twist_msg);
00387     error_pub_.publish(error_msg);
00388 }
00389 
00390 bool CobFrameTracker::startTrackingCallback(cob_srvs::SetString::Request& request, cob_srvs::SetString::Response& response)
00391 {
00392     if (tracking_)
00393     {
00394         std::string msg = "CobFrameTracker: StartTracking denied because Tracking already active";
00395         ROS_ERROR_STREAM(msg);
00396         response.success = false;
00397         response.message = msg;
00398     }
00399     else if (tracking_goal_)
00400     {
00401         std::string msg = "CobFrameTracker: StartTracking denied because TrackingAction is active";
00402         ROS_ERROR_STREAM(msg);
00403         response.success = false;
00404         response.message = msg;
00405     }
00406     else if (lookat_)
00407     {
00408         std::string msg = "CobFrameTracker: StartTracking denied because Lookat is active";
00409         ROS_ERROR_STREAM(msg);
00410         response.success = false;
00411         response.message = msg;
00412     }
00413     else
00414     {
00415         // check whether given target frame exists
00416         if (!tf_listener_.frameExists(request.data))
00417         {
00418             std::string msg = "CobFrameTracker: StartTracking denied because target frame '" + request.data + "' does not exist";
00419             ROS_ERROR_STREAM(msg);
00420             response.success = false;
00421             response.message = msg;
00422         }
00423         else
00424         {
00425             std::string msg = "CobFrameTracker: StartTracking started with CART_DIST_SECURITY MONITORING enabled";
00426             ROS_INFO_STREAM(msg);
00427             response.success = true;
00428             response.message = msg;
00429 
00430             tracking_ = true;
00431             tracking_goal_ = false;
00432             lookat_ = false;
00433             tracking_frame_ = chain_tip_link_;
00434             target_frame_ = request.data;
00435         }
00436     }
00437     return true;
00438 }
00439 
00440 bool CobFrameTracker::startLookatCallback(cob_srvs::SetString::Request& request, cob_srvs::SetString::Response& response)
00441 {
00442     if (tracking_)
00443     {
00444         std::string msg = "CobFrameTracker: StartLookat denied because Tracking active";
00445         ROS_ERROR_STREAM(msg);
00446         response.success = false;
00447         response.message = msg;
00448     }
00449     else if (tracking_goal_)
00450     {
00451         std::string msg = "CobFrameTracker: StartLookat denied because TrackingAction is active";
00452         ROS_ERROR_STREAM(msg);
00453         response.success = false;
00454         response.message = msg;
00455     }
00456     else if (lookat_)
00457     {
00458         std::string msg = "CobFrameTracker: StartLookat denied because Lookat is already active";
00459         ROS_ERROR_STREAM(msg);
00460         response.success = false;
00461         response.message = msg;
00462     }
00463     else
00464     {
00465         // check whether given target frame exists
00466         if (!tf_listener_.frameExists(request.data))
00467         {
00468             std::string msg = "CobFrameTracker: StartLookat denied because target frame '" + request.data + "' does not exist";
00469             ROS_ERROR_STREAM(msg);
00470             response.success = false;
00471             response.message = msg;
00472         }
00473         else
00474         {
00475             dynamic_reconfigure::Reconfigure srv;
00476             dynamic_reconfigure::IntParameter int_param;
00477             int_param.name = "kinematic_extension";
00478             int_param.value = 4;    // LOOKAT
00479             srv.request.config.ints.push_back(int_param);
00480 
00481             bool success = reconfigure_client_.call(srv);
00482 
00483             if (success)
00484             {
00485                 std::string msg = "CobFrameTracker: StartLookat started with CART_DIST_SECURITY MONITORING enabled";
00486                 ROS_INFO_STREAM(msg);
00487                 response.success = true;
00488                 response.message = msg;
00489 
00490                 tracking_ = false;
00491                 tracking_goal_ = false;
00492                 lookat_ = true;
00493                 tracking_frame_ = lookat_focus_frame_;
00494                 target_frame_ = request.data;
00495             }
00496             else
00497             {
00498                 std::string msg = "CobFrameTracker: StartLookat denied because DynamicReconfigure failed";
00499                 ROS_ERROR_STREAM(msg);
00500                 response.success = false;
00501                 response.message = msg;
00502             }
00503         }
00504     }
00505     return true;
00506 }
00507 
00508 bool CobFrameTracker::stopCallback(std_srvs::Trigger::Request& request, std_srvs::Trigger::Response& response)
00509 {
00510     if (tracking_goal_)
00511     {
00512         std::string msg = "CobFrameTracker: Stop denied because TrackingAction is active";
00513         ROS_ERROR_STREAM(msg);
00514         response.success = false;
00515         response.message = msg;
00516     }
00517     else if (tracking_ || lookat_)
00518     {
00519         if (lookat_)
00520         {
00521             // disable LOOKAT in dynamic_reconfigure server
00522             dynamic_reconfigure::Reconfigure srv;
00523             dynamic_reconfigure::IntParameter int_param;
00524             int_param.name = "kinematic_extension";
00525             int_param.value = 0;    // NO_EXTENSION
00526             srv.request.config.ints.push_back(int_param);
00527 
00528             if (!reconfigure_client_.call(srv))
00529             {
00530                 std::string msg = "CobFrameTracker: Stop failed to disable LOOKAT_EXTENSION. Stopping anyway!";
00531                 ROS_ERROR_STREAM(msg);
00532             }
00533         }
00534 
00535         std::string msg = "CobFrameTracker: Stop successful";
00536         ROS_INFO_STREAM(msg);
00537         response.success = true;
00538         response.message = msg;
00539 
00540         tracking_ = false;
00541         tracking_goal_ = false;
00542         lookat_ = false;
00543         tracking_frame_ = chain_tip_link_;
00544         target_frame_ = tracking_frame_;
00545 
00546         publishZeroTwist();
00547     }
00548     else
00549     {
00550         std::string msg = "CobFrameTracker: Stop failed because nothing was tracked";
00551         ROS_ERROR_STREAM(msg);
00552         response.success = false;
00553         response.message = msg;
00554     }
00555     return true;
00556 }
00557 
00558 void CobFrameTracker::goalCB()
00559 {
00560     ROS_INFO("Received a new goal");
00561     if (as_->isNewGoalAvailable())
00562     {
00563         boost::shared_ptr<const cob_frame_tracker::FrameTrackingGoal> goal_ = as_->acceptNewGoal();
00564 
00565         if (tracking_ || lookat_)
00566         {
00567             // Goal should not be accepted
00568             ROS_ERROR_STREAM("CobFrameTracker: Received ActionGoal while tracking/lookat Service is active!");
00569         }
00570         else if (!tf_listener_.frameExists(goal_->tracking_frame))
00571         {
00572             // Goal should not be accepted
00573             ROS_ERROR_STREAM("CobFrameTracker: Received ActionGoal but target frame '" << goal_->tracking_frame << "' does not exist");
00574         }
00575         else
00576         {
00577             target_frame_ = goal_->tracking_frame;
00578             tracking_duration_ = goal_->tracking_duration;
00579             stop_on_goal_ = goal_->stop_on_goal;
00580             tracking_ = false;
00581             tracking_goal_ = true;
00582             lookat_ = false;
00583             abortion_counter_ = 0;
00584             tracking_start_time_ = ros::Time::now();
00585         }
00586     }
00587 }
00588 
00589 void CobFrameTracker::preemptCB()
00590 {
00591     ROS_WARN("Received a preemption request");
00592     action_result_.success = true;
00593     action_result_.message = "Action has been preempted";
00594     as_->setPreempted(action_result_);
00595     tracking_ = false;
00596     tracking_goal_ = false;
00597     lookat_ = false;
00598     tracking_frame_ = chain_tip_link_;
00599     target_frame_ = tracking_frame_;
00600 
00601     publishZeroTwist();
00602 }
00603 
00604 void CobFrameTracker::action_success()
00605 {
00606     ROS_INFO("Goal succeeded!");
00607     as_->setSucceeded(action_result_, action_result_.message);
00608 
00609     tracking_ = false;
00610     tracking_goal_ = false;
00611     lookat_ = false;
00612     tracking_frame_ = chain_tip_link_;
00613     target_frame_ = tracking_frame_;
00614 
00615     publishZeroTwist();
00616 }
00617 
00618 void CobFrameTracker::action_abort()
00619 {
00620     ROS_WARN("Goal aborted");
00621     as_->setAborted(action_result_, action_result_.message);
00622 
00623     tracking_ = false;
00624     tracking_goal_ = false;
00625     lookat_ = false;
00626     tracking_frame_ = chain_tip_link_;
00627     target_frame_ = tracking_frame_;
00628 
00629     publishZeroTwist();
00630 }
00631 
00632 int CobFrameTracker::checkStatus()
00633 {
00634     int status = 0;
00635 
00636     if (!enable_abortion_checking_)
00637     {
00638         abortion_counter_ = 0;
00639         return status;
00640     }
00641 
00642     if (ros::Time::now() > tracking_start_time_ + ros::Duration(tracking_duration_))
00643     {
00644         action_result_.success = true;
00645         action_result_.message = std::string("Successfully tracked goal for %f seconds", tracking_duration_);
00646         status = 1;
00647     }
00648 
00649     bool infinitesimal_twist = checkInfinitesimalTwist(current_twist_);
00650     bool distance_violation = checkCartDistanceViolation(cart_distance_, rot_distance_);
00651     bool twist_violation = checkTwistViolation(current_twist_, target_twist_);
00652 
00653     if (stop_on_goal_)
00654     {
00656         if (infinitesimal_twist && !distance_violation && !twist_violation)
00657         {
00658             action_result_.success = true;
00659             action_result_.message = "Successfully reached goal";
00660             status = 2;
00661         }
00662     }
00663 
00664     if (distance_violation || twist_violation)
00665     {
00666         ROS_ERROR_STREAM("distance_violation || twist_violation");
00667         abortion_counter_++;
00668     }
00669 
00670     if (abortion_counter_ > max_abortions_)
00671     {
00672         action_result_.success = false;
00673         action_result_.message = "Constraints violated. Action aborted";
00674         status = -1;
00675     }
00676 
00677     return status;
00678 }
00679 
00680 
00681 int CobFrameTracker::checkServiceCallStatus()
00682 {
00683     int status = 0;
00684 
00685     if (!enable_abortion_checking_)
00686     {
00687         abortion_counter_ = 0;
00688         return status;
00689     }
00690 
00691     bool distance_violation = checkCartDistanceViolation(cart_distance_, rot_distance_);
00692 
00693     if (distance_violation)
00694     {
00695         abortion_counter_++;
00696     }
00697     else
00698     {
00699         abortion_counter_ = abortion_counter_ > 0 ? abortion_counter_ - 1 : 0;
00700     }
00701 
00702     if (abortion_counter_ >= max_abortions_)
00703     {
00704         abortion_counter_ = max_abortions_;
00705         status = -1;
00706     }
00707 
00708     return status;
00709 }
00710 
00711 
00712 void CobFrameTracker::jointstateCallback(const sensor_msgs::JointState::ConstPtr& msg)
00713 {
00714     KDL::JntArray q_temp = last_q_;
00715     KDL::JntArray q_dot_temp = last_q_dot_;
00716     int count = 0;
00717     for (unsigned int j = 0; j < dof_; j++)
00718     {
00719         for (unsigned int i = 0; i < msg->name.size(); i++)
00720         {
00721             if (strcmp(msg->name[i].c_str(), joints_[j].c_str()) == 0)
00722             {
00723                 q_temp(j) = msg->position[i];
00724                 q_dot_temp(j) = msg->velocity[i];
00725                 count++;
00726                 break;
00727             }
00728         }
00729     }
00730     if (count == joints_.size())
00731     {
00732         last_q_ = q_temp;
00733         last_q_dot_ = q_dot_temp;
00735         KDL::FrameVel FrameVel;
00736         KDL::JntArrayVel jntArrayVel = KDL::JntArrayVel(last_q_, last_q_dot_);
00737         jntToCartSolver_vel_.reset(new KDL::ChainFkSolverVel_recursive(chain_));
00738         int ret = jntToCartSolver_vel_->JntToCart(jntArrayVel, FrameVel, -1);
00739         if (ret >= 0)
00740         {
00741             KDL::Twist twist = FrameVel.GetTwist();
00742             current_twist_ = twist;
00743         }
00744         else
00745         {
00746             ROS_ERROR("ChainFkSolverVel failed!");
00747         }
00749     }
00750 }
00751 
00752 void CobFrameTracker::reconfigureCallback(cob_frame_tracker::FrameTrackerConfig& config, uint32_t level)
00753 {
00754     enable_abortion_checking_ = config.enable_abortion_checking;
00755     cart_min_dist_threshold_lin_ = config.cart_min_dist_threshold_lin;
00756     cart_min_dist_threshold_rot_ = config.cart_min_dist_threshold_rot;
00757     twist_dead_threshold_lin_ = config.twist_dead_threshold_lin;
00758     twist_dead_threshold_rot_ = config.twist_dead_threshold_rot;
00759     twist_deviation_threshold_lin_ = config.twist_deviation_threshold_lin;
00760     twist_deviation_threshold_rot_ = config.twist_deviation_threshold_rot;
00761 }
00762 
00764 bool CobFrameTracker::checkInfinitesimalTwist(const KDL::Twist current)
00765 {
00766     if (fabs(current.vel.x()) > twist_dead_threshold_lin_)
00767     {
00768         return false;
00769     }
00770     if (fabs(current.vel.y()) > twist_dead_threshold_lin_)
00771     {
00772         return false;
00773     }
00774     if (fabs(current.vel.z()) > twist_dead_threshold_lin_)
00775     {
00776         return false;
00777     }
00778     if (fabs(current.rot.x()) > twist_dead_threshold_rot_)
00779     {
00780         return false;
00781     }
00782     if (fabs(current.rot.y()) > twist_dead_threshold_rot_)
00783     {
00784         return false;
00785     }
00786     if (fabs(current.rot.z()) > twist_dead_threshold_rot_)
00787     {
00788         return false;
00789     }
00790 
00792     return true;
00793 }
00794 
00796 bool CobFrameTracker::checkCartDistanceViolation(const double dist, const double rot)
00797 {
00798     if (dist > cart_min_dist_threshold_lin_)
00799     {
00800         return true;
00801     }
00802     if (rot > cart_min_dist_threshold_rot_)
00803     {
00804         return true;
00805     }
00806 
00808     return false;
00809 }
00810 
00812 bool CobFrameTracker::checkTwistViolation(const KDL::Twist current, const KDL::Twist target)
00813 {
00814     if (fabs(current.vel.x() - target.vel.x()) > twist_deviation_threshold_lin_)
00815     {
00816         return true;
00817     }
00818     if (fabs(current.vel.y() - target.vel.y()) > twist_deviation_threshold_lin_)
00819     {
00820         return true;
00821     }
00822     if (fabs(current.vel.z() - target.vel.z()) > twist_deviation_threshold_lin_)
00823     {
00824         return true;
00825     }
00826     if (fabs(current.rot.x() - target.rot.x()) > twist_deviation_threshold_rot_)
00827     {
00828         return true;
00829     }
00830     if (fabs(current.rot.y() - target.rot.y()) > twist_deviation_threshold_rot_)
00831     {
00832         return true;
00833     }
00834     if (fabs(current.rot.z() - target.rot.z()) > twist_deviation_threshold_rot_)
00835     {
00836         return true;
00837     }
00838 
00840     return false;
00841 }


cob_frame_tracker
Author(s): Felix Messmer
autogenerated on Thu Jun 6 2019 21:19:08