42 #include <std_msgs/Bool.h>
43 #include <std_msgs/Float64MultiArray.h>
48 static const std::string
LOGNAME =
"servo_calcs";
56 bool isNonZero(
const geometry_msgs::TwistStamped& msg)
58 return msg.twist.linear.x != 0.0 || msg.twist.linear.y != 0.0 || msg.twist.linear.z != 0.0 ||
59 msg.twist.angular.x != 0.0 || msg.twist.angular.y != 0.0 || msg.twist.angular.z != 0.0;
63 bool isNonZero(
const control_msgs::JointJog& msg)
65 bool all_zeros =
true;
66 for (
double delta : msg.velocities)
68 all_zeros &= (delta == 0.0);
74 geometry_msgs::TransformStamped convertIsometryToTransform(
const Eigen::Isometry3d& eigen_tf,
75 const std::string& parent_frame,
76 const std::string& child_frame)
79 output.header.frame_id = parent_frame;
80 output.child_frame_id = child_frame;
90 , parameters_(parameters)
92 , stop_requested_(true)
151 Eigen::Matrix3d empty_matrix;
152 empty_matrix.setZero();
168 auto initial_joint_trajectory = moveit::util::make_shared_from_pool<trajectory_msgs::JointTrajectory>();
172 initial_joint_trajectory->header.stamp =
ros::Time(0);
175 trajectory_msgs::JointTrajectoryPoint
point;
184 point.velocities = velocity;
193 initial_joint_trajectory->points.push_back(
point);
271 auto status_msg = moveit::util::make_shared_from_pool<std_msgs::Int8>();
331 auto joint_trajectory = moveit::util::make_shared_from_pool<trajectory_msgs::JointTrajectory>();
355 for (
auto&
point : joint_trajectory->points)
358 point.velocities.assign(
point.velocities.size(), 0);
359 point.accelerations.assign(
point.accelerations.size(), 0);
368 "Try a larger 'incoming_command_timeout' parameter?");
413 joint_trajectory->header.stamp =
ros::Time(0);
418 auto joints = moveit::util::make_shared_from_pool<std_msgs::Float64MultiArray>();
420 joints->data = joint_trajectory->points[0].positions;
422 joints->data = joint_trajectory->points[0].velocities;
435 trajectory_msgs::JointTrajectory& joint_trajectory)
438 if (std::isnan(
cmd.twist.linear.x) || std::isnan(
cmd.twist.linear.y) || std::isnan(
cmd.twist.linear.z) ||
439 std::isnan(
cmd.twist.angular.x) || std::isnan(
cmd.twist.angular.y) || std::isnan(
cmd.twist.angular.z))
442 "nan in incoming command. Skipping this datapoint.");
449 if ((fabs(
cmd.twist.linear.x) > 1) || (fabs(
cmd.twist.linear.y) > 1) || (fabs(
cmd.twist.linear.z) > 1) ||
450 (fabs(
cmd.twist.angular.x) > 1) || (fabs(
cmd.twist.angular.y) > 1) || (fabs(
cmd.twist.angular.z) > 1))
453 "Component of incoming command is >1. Skipping this datapoint.");
460 cmd.twist.linear.x = 0;
462 cmd.twist.linear.y = 0;
464 cmd.twist.linear.z = 0;
466 cmd.twist.angular.x = 0;
468 cmd.twist.angular.y = 0;
470 cmd.twist.angular.z = 0;
475 Eigen::Vector3d translation_vector(
cmd.twist.linear.x,
cmd.twist.linear.y,
cmd.twist.linear.z);
476 Eigen::Vector3d angular_vector(
cmd.twist.angular.x,
cmd.twist.angular.y,
cmd.twist.angular.z);
494 const auto tf_moveit_to_incoming_cmd_frame =
498 translation_vector = tf_moveit_to_incoming_cmd_frame.linear() * translation_vector;
499 angular_vector = tf_moveit_to_incoming_cmd_frame.linear() * angular_vector;
504 cmd.twist.linear.x = translation_vector(0);
505 cmd.twist.linear.y = translation_vector(1);
506 cmd.twist.linear.z = translation_vector(2);
507 cmd.twist.angular.x = angular_vector(0);
508 cmd.twist.angular.y = angular_vector(1);
509 cmd.twist.angular.z = angular_vector(2);
521 for (
auto dimension = jacobian.rows() - 1; dimension >= 0; --dimension)
529 Eigen::JacobiSVD<Eigen::MatrixXd> svd =
530 Eigen::JacobiSVD<Eigen::MatrixXd>(jacobian, Eigen::ComputeThinU | Eigen::ComputeThinV);
531 Eigen::MatrixXd matrix_s = svd.singularValues().asDiagonal();
532 Eigen::MatrixXd pseudo_inverse = svd.matrixV() * matrix_s.inverse() * svd.matrixU().transpose();
549 for (
double velocity :
cmd.velocities)
551 if (std::isnan(velocity))
554 "nan in incoming command. Skipping this datapoint.");
604 joint_trajectory.points.resize(count);
605 auto point = joint_trajectory.points[0];
608 for (
int i = 1; i < count; ++i)
611 joint_trajectory.points[i] =
point;
637 for (
int i = 0; i < delta_theta.size(); ++i)
644 trajectory_msgs::JointTrajectory& joint_trajectory)
const
648 joint_trajectory.header.stamp =
ros::Time(0);
650 joint_trajectory.joint_names = joint_state.name;
652 trajectory_msgs::JointTrajectoryPoint
point;
655 point.positions = joint_state.position;
657 point.velocities = joint_state.velocity;
664 point.accelerations = acceleration;
666 joint_trajectory.points.push_back(
point);
674 if (collision_scale > 0 && collision_scale < 1)
679 else if (collision_scale == 0)
684 delta_theta = collision_scale * singularity_scale * delta_theta;
695 const Eigen::JacobiSVD<Eigen::MatrixXd>& svd,
696 const Eigen::MatrixXd& pseudo_inverse)
698 double velocity_scale = 1;
699 std::size_t num_dimensions = commanded_velocity.size();
705 Eigen::VectorXd vector_toward_singularity = svd.matrixU().col(num_dimensions - 1);
707 double ini_condition = svd.singularValues()(0) / svd.singularValues()(svd.singularValues().size() - 1);
713 Eigen::VectorXd delta_x(num_dimensions);
715 delta_x = vector_toward_singularity / scale;
718 Eigen::VectorXd new_theta;
720 new_theta += pseudo_inverse * delta_x;
724 Eigen::JacobiSVD<Eigen::MatrixXd> new_svd(new_jacobian);
725 double new_condition = new_svd.singularValues()(0) / new_svd.singularValues()(new_svd.singularValues().size() - 1);
727 if (new_condition < ini_condition)
729 vector_toward_singularity *= -1;
733 double dot = vector_toward_singularity.dot(commanded_velocity);
756 return velocity_scale;
764 std::size_t joint_delta_index{ 0 };
765 double velocity_scaling_factor{ 1.0 };
768 const auto& bounds = joint->getVariableBounds(joint->getName());
769 if (bounds.velocity_bounded_ && velocity(joint_delta_index) != 0.0)
771 const double unbounded_velocity = velocity(joint_delta_index);
773 const auto bounded_velocity = std::min(std::max(unbounded_velocity, bounds.min_velocity_), bounds.max_velocity_);
774 velocity_scaling_factor = std::min(velocity_scaling_factor, bounded_velocity / unbounded_velocity);
785 bool halting =
false;
790 double joint_angle = 0;
801 const std::vector<moveit_msgs::JointLimits>& limits = joint->getVariableBoundsMsg();
807 auto joint_itr = std::find(joint_state.name.begin(), joint_state.name.end(), joint->getName());
808 auto joint_idx = std::distance(joint_state.name.begin(), joint_itr);
810 if ((joint_state.velocity.at(joint_idx) < 0 &&
812 (joint_state.velocity.at(joint_idx) > 0 &&
818 " position limit. Halting.");
832 joint_trajectory.points.clear();
833 joint_trajectory.points.emplace_back();
834 trajectory_msgs::JointTrajectoryPoint&
point = joint_trajectory.points.front();
840 point.time_from_start.fromNSec(1);
859 point.velocities[i] = 0;
875 std::string joint_name =
"";
877 double accel_limit = 0;
878 double joint_velocity = 0;
879 double worst_case_stop_time = 0;
887 if (joint_model->getName() == joint_name)
889 kinematic_bounds = joint_model->getVariableBounds();
891 if (kinematic_bounds[0].acceleration_bounded_)
895 std::min(fabs(kinematic_bounds[0].min_acceleration_), fabs(kinematic_bounds[0].max_acceleration_));
900 "An acceleration limit is not defined for this joint; minimum stop distance "
901 "should not be used for collision checking");
911 worst_case_stop_time = std::max(worst_case_stop_time, fabs(joint_velocity / accel_limit));
916 auto msg = moveit::util::make_shared_from_pool<std_msgs::Float64>();
917 msg->data = worst_case_stop_time;
925 Eigen::VectorXd result(6);
959 for (std::size_t
m = 0;
m <
command.joint_names.size(); ++
m)
965 catch (
const std::out_of_range& e)
986 for (std::size_t i = 0, size =
static_cast<std::size_t
>(increments.size()); i < size; ++i)
990 output.position[i] += increments[i];
992 catch (
const std::out_of_range& e)
996 "increments do not match.");
1006 unsigned int num_rows = jacobian.rows() - 1;
1007 unsigned int num_cols = jacobian.cols();
1009 if (row_to_remove < num_rows)
1011 jacobian.block(row_to_remove, 0, num_rows - row_to_remove, num_cols) =
1012 jacobian.block(row_to_remove + 1, 0, num_rows - row_to_remove, num_cols);
1013 delta_x.segment(row_to_remove, num_rows - row_to_remove) =
1014 delta_x.segment(row_to_remove + 1, num_rows - row_to_remove);
1016 jacobian.conservativeResize(num_rows, num_cols);
1017 delta_x.conservativeResize(num_rows);
1099 moveit_msgs::ChangeDriftDimensions::Response& res)
1113 moveit_msgs::ChangeControlDimensions::Response& res)