27 #include <visualization_msgs/Marker.h>
28 #include <visualization_msgs/MarkerArray.h>
29 #include <cob_srvs/SetString.h>
31 #include <Eigen/Dense>
40 ROS_ERROR(
"Parameter 'joint_names' not set");
49 ROS_ERROR(
"Parameter 'chain_base_link' not set");
55 ROS_ERROR(
"Parameter 'chain_tip_link' not set");
62 ROS_WARN_STREAM(
"Parameter 'collision_check_links' not set. Collision Avoidance constraint will not do anything.");
70 ROS_ERROR(
"Failed to construct kdl tree");
75 if (
chain_.getNrOfJoints() == 0)
77 ROS_ERROR(
"Failed to initialize kinematic chain");
83 if (!model.
initParam(
"/robot_description"))
85 ROS_ERROR(
"Failed to parse urdf file for JointLimits");
115 if (nh_twist.
hasParam(
"lookat_axis_type"))
117 int lookat_axis_type;
118 nh_twist.
getParam(
"lookat_axis_type", lookat_axis_type);
121 if (nh_twist.
hasParam(
"lookat_pointing_frame"))
127 if (nh_twist.
hasParam(
"lookat_offset"))
129 if (nh_twist.
hasParam(
"lookat_offset/translation"))
135 if (nh_twist.
hasParam(
"lookat_offset/rotation"))
148 ROS_ERROR(
"Parameter 'controller_interface' not set");
160 ROS_ERROR(
"The controller_interface plugin failed to load. Error: %s", ex.what());
165 for (uint16_t i = 0; i <
chain_.getNrOfSegments(); ++i)
208 "No collision_check_links set for this chain. Nothing will be registered. Ensure parameters are set correctly.");
215 cob_srvs::SetString
r;
216 r.request.data = *it;
219 ROS_INFO_STREAM(
"Called registration service with success: " <<
int(
r.response.success) <<
". Got message: " <<
r.response.message);
220 if (!
r.response.success)
244 ROS_ERROR_STREAM(
"ResetAll during DynamicReconfigureCallback failed! Resetting to previous config");
261 config.damping_factor = 0.01;
266 config.w_threshold = 0.005;
271 config.w_threshold = 0.005;
275 config.lambda_max = 0.001;
276 config.w_threshold = 0.001;
284 ROS_ERROR(
"The selection of Default solver and a constraint doesn\'t make any sense. Switch settings back ...");
294 ROS_ERROR(
"The WLN solution doesn\'t support collision avoidance. Currently WLN is only implemented for Identity and JLA ...");
302 ROS_ERROR(
"You have chosen GPM but without constraints! The behaviour without constraints will be the same like for DEFAULT_SOLVER.");
308 ROS_ERROR(
"The projection of a task into the null space of the main EE task is currently only for the CA constraint supported!");
318 ROS_ERROR(
"The Unified JLA and SA solution doesn\'t support collision avoidance. Currently UNIFIED_JLA_SA is only implemented for SA and JLA ...");
328 ROS_ERROR(
"ServiceServer 'obstacle_distance/registerLinkOfInterest' does not exist. CA not possible");
335 ROS_INFO(
"Collision Avoidance has been activated! Register links!");
338 ROS_ERROR(
"Registration of links failed. CA not possible");
348 ROS_ERROR(
"The limits_tolerance for enforce limits is smaller than DIV/0 threshold. Therefore output limiting is disabled");
356 ROS_ERROR(
"The limits used to limit Cartesian velocities are smaller than DIV/0 threshold. Therefore input limiting is disabled");
362 ROS_INFO(
"Parameters seem to be ok.");
371 KDL::Twist twist, twist_transformed;
380 ROS_ERROR(
"CobTwistController::twistStampedCallback: \n%s", ex.what());
385 twist_transformed = frame*twist;
405 KDL::JntArray q_dot_ik(
chain_.getNrOfJoints());
444 ROS_ERROR(
"CobTwistController::visualizeTwist: \n%s", ex.what());
448 visualization_msgs::Marker marker_vel;
451 marker_vel.ns =
"twist_vel";
453 marker_vel.type = visualization_msgs::Marker::ARROW;
454 marker_vel.action = visualization_msgs::Marker::ADD;
456 marker_vel.pose.orientation.w = 1.0;
458 marker_vel.scale.x = 0.02;
459 marker_vel.scale.y = 0.02;
460 marker_vel.scale.z = 0.02;
462 marker_vel.color.r = 1.0f;
463 marker_vel.color.g = 1.0f;
464 marker_vel.color.b = 0.0f;
465 marker_vel.color.a = 1.0;
467 marker_vel.points.resize(2);
468 marker_vel.points[0].x = transform_tf.
getOrigin().x();
469 marker_vel.points[0].y = transform_tf.
getOrigin().y();
470 marker_vel.points[0].z = transform_tf.
getOrigin().z();
471 marker_vel.points[1].x = transform_tf.
getOrigin().x() + 5.0 * twist.vel.x();
472 marker_vel.points[1].y = transform_tf.
getOrigin().y() + 5.0 * twist.vel.y();
473 marker_vel.points[1].z = transform_tf.
getOrigin().z() + 5.0 * twist.vel.z();
475 visualization_msgs::Marker marker_rot;
478 marker_rot.ns =
"twist_rot";
480 marker_rot.type = visualization_msgs::Marker::CYLINDER;
481 marker_rot.action = visualization_msgs::Marker::ADD;
483 marker_rot.pose.position.x = transform_tf.
getOrigin().x();
484 marker_rot.pose.position.y = transform_tf.
getOrigin().y();
485 marker_rot.pose.position.z = transform_tf.
getOrigin().z();
488 rot.
setRPY(twist.rot.x(), twist.rot.y(), twist.rot.z());
491 tf::Vector3 z_axis = tf::Vector3(0, 0, 1);
492 tf::Vector3 t_axis = rot.
getAxis();
494 if (z_axis != t_axis && z_axis != -t_axis)
496 tf::Vector3 cross = z_axis.cross(t_axis);
497 temp =
tf::Quaternion(cross.x(), cross.y(), cross.z(), (std::sqrt(z_axis.length2() * t_axis.length2()) + z_axis.dot(t_axis)));
502 marker_rot.scale.x = rot.
getAngle();
503 marker_rot.scale.y = rot.
getAngle();
504 marker_rot.scale.z = 0.002;
506 marker_rot.color.r = 1.0f;
507 marker_rot.color.g = 1.0f;
508 marker_rot.color.b = 0.0f;
509 marker_rot.color.a = 1.0;
511 visualization_msgs::MarkerArray markers;
512 markers.markers.push_back(marker_vel);
513 markers.markers.push_back(marker_rot);
526 for (uint16_t i = 0; i <
msg->name.size(); i++)
530 q_temp(j) =
msg->position[i];
531 q_dot_temp(j) =
msg->velocity[i];
549 KDL::Twist twist_odometry_bl, tangential_twist_bl, twist_odometry_transformed_cb;
550 KDL::Frame cb_frame_bl;
566 ROS_ERROR(
"CobTwistController::odometryCallback: \n%s", ex.what());
574 Eigen::Vector3d w(0, 0,
msg->twist.twist.angular.z);
575 Eigen::Vector3d res = w.cross(
r);
576 tangential_twist_bl.vel = KDL::Vector(res(0), res(1), res(2));
577 tangential_twist_bl.rot = KDL::Vector(0, 0, 0);
581 ROS_ERROR(
"Error occurred while calculating tangential twist for angular base movements.");
588 twist_odometry_transformed_cb = cb_frame_bl * (twist_odometry_bl + tangential_twist_bl);