23 #include <geometry_msgs/Twist.h>
24 #include <sensor_msgs/JointState.h>
26 #include <cob_frame_tracker/FrameTrackingAction.h>
29 #include <kdl/chainiksolvervel_pinv.hpp>
30 #include <kdl/chainfksolvervel_recursive.hpp>
31 #include <kdl/jntarray.hpp>
32 #include <kdl/jntarrayvel.hpp>
42 if (nh_tracker.
hasParam(
"update_rate"))
53 ROS_ERROR(
"No chain_base_link specified. Aborting!");
63 ROS_ERROR(
"No chain_tip_link specified. Aborting!");
69 ROS_ERROR(
"Parameter 'joint_names' not set");
76 ROS_ERROR(
"Failed to construct kdl tree");
81 if (
chain_.getNrOfJoints() == 0)
83 ROS_ERROR(
"Failed to initialize kinematic chain");
92 if (nh_tracker.
hasParam(
"movable_trans"))
96 if (nh_tracker.
hasParam(
"movable_rot"))
101 if (nh_tracker.
hasParam(
"max_vel_lin"))
106 if (nh_tracker.
hasParam(
"max_vel_rot"))
217 bool transform =
false;
227 ROS_ERROR(
"CobFrameTracker::getTransform: \n%s", ex.what());
236 geometry_msgs::TwistStamped twist_msg;
239 twist_msg.header.stamp = now;
248 geometry_msgs::TwistStamped twist_msg, error_msg;
251 twist_msg.header.stamp = now;
253 error_msg.header.stamp = now;
257 ROS_WARN(
"publishTwist: failed to getTransform");
261 double error_trans_x = transform_tf.
getOrigin().x();
262 double error_trans_y = transform_tf.
getOrigin().y();
263 double error_trans_z = transform_tf.
getOrigin().z();
264 double error_rot_x = transform_tf.
getRotation().x();
265 double error_rot_y = transform_tf.
getRotation().y();
266 double error_rot_z = transform_tf.
getRotation().z();
268 error_msg.twist.linear.x = error_trans_x;
269 error_msg.twist.linear.y = error_trans_y;
270 error_msg.twist.linear.z = error_trans_z;
271 error_msg.twist.angular.x = error_rot_x;
272 error_msg.twist.angular.y = error_rot_y;
273 error_msg.twist.angular.z = error_rot_z;
343 geometry_msgs::TwistStamped twist_msg, error_msg;
346 twist_msg.header.stamp = now;
348 error_msg.header.stamp = now;
369 error_msg.twist.linear.x = error_trans_x;
370 error_msg.twist.linear.y = error_trans_y;
371 error_msg.twist.linear.z = error_trans_z;
372 error_msg.twist.angular.x = error_rot_x;
373 error_msg.twist.angular.y = error_rot_y;
374 error_msg.twist.angular.z = error_rot_z;
394 std::string msg =
"CobFrameTracker: StartTracking denied because Tracking already active";
401 std::string msg =
"CobFrameTracker: StartTracking denied because TrackingAction is active";
408 std::string msg =
"CobFrameTracker: StartTracking denied because Lookat is active";
418 std::string msg =
"CobFrameTracker: StartTracking denied because target frame '" + request.data +
"' does not exist";
425 std::string msg =
"CobFrameTracker: StartTracking started with CART_DIST_SECURITY MONITORING enabled";
444 std::string msg =
"CobFrameTracker: StartLookat denied because Tracking active";
451 std::string msg =
"CobFrameTracker: StartLookat denied because TrackingAction is active";
458 std::string msg =
"CobFrameTracker: StartLookat denied because Lookat is already active";
468 std::string msg =
"CobFrameTracker: StartLookat denied because target frame '" + request.data +
"' does not exist";
475 dynamic_reconfigure::Reconfigure srv;
476 dynamic_reconfigure::IntParameter int_param;
477 int_param.name =
"kinematic_extension";
479 srv.request.config.ints.push_back(int_param);
482 ROS_DEBUG_STREAM(
"srv.request: " << srv.request <<
", srv.response: " << srv.response);
487 for (std::vector<dynamic_reconfigure::IntParameter>::iterator it = srv.response.config.ints.begin() ; it != srv.response.config.ints.end(); ++it)
489 if (it->name == int_param.name && it->value == int_param.value)
498 std::string msg =
"CobFrameTracker: StartLookat started with CART_DIST_SECURITY MONITORING enabled";
511 std::string msg =
"CobFrameTracker: StartLookat denied because DynamicReconfigure failed to set vaulues";
519 std::string msg =
"CobFrameTracker: StartLookat denied because DynamicReconfigure failed to call service";
533 std::string msg =
"CobFrameTracker: Stop denied because TrackingAction is active";
543 dynamic_reconfigure::Reconfigure srv;
544 dynamic_reconfigure::IntParameter int_param;
545 int_param.name =
"kinematic_extension";
547 srv.request.config.ints.push_back(int_param);
551 std::string msg =
"CobFrameTracker: Stop failed to disable LOOKAT_EXTENSION. Stopping anyway!";
556 std::string msg =
"CobFrameTracker: Stop successful";
571 std::string msg =
"CobFrameTracker: Stop failed because nothing was tracked";
582 if (
as_->isNewGoalAvailable())
589 ROS_ERROR_STREAM(
"CobFrameTracker: Received ActionGoal while tracking/lookat Service is active!");
594 ROS_ERROR_STREAM(
"CobFrameTracker: Received ActionGoal but target frame '" << goal_->tracking_frame <<
"' does not exist");
612 ROS_WARN(
"Received a preemption request");
677 if (infinitesimal_twist && !distance_violation && !twist_violation)
685 if (distance_violation || twist_violation)
714 if (distance_violation)
735 KDL::JntArray q_temp =
last_q_;
738 for (
unsigned int j = 0; j <
dof_; j++)
740 for (
unsigned int i = 0; i < msg->name.size(); i++)
742 if (strcmp(msg->name[i].c_str(),
joints_[j].c_str()) == 0)
744 q_temp(j) = msg->position[i];
745 q_dot_temp(j) = msg->velocity[i];
756 KDL::FrameVel FrameVel;
762 KDL::Twist twist = FrameVel.GetTwist();