moveit2
The MoveIt Motion Planning Framework for ROS 2.
command.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2019, Los Alamos National Security, LLC
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE
25  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32  *******************************************************************************/
33 
34 /* Title : command.cpp
35  * Project : moveit_servo
36  * Created : 06/04/2023
37  * Author : Brian O'Neil, Andy Zelenak, Blake Anderson, V Mohammed Ibrahim
38  */
39 
41 #include <moveit/utils/logger.hpp>
42 
43 namespace
44 {
45 rclcpp::Logger getLogger()
46 {
47  return moveit::getLogger("moveit.ros.servo");
48 }
49 
60 const Eigen::VectorXd createMoveGroupDelta(const Eigen::VectorXd& sub_group_deltas,
61  const moveit::core::RobotStatePtr& robot_state,
62  const servo::Params& servo_params,
63  const moveit_servo::JointNameToMoveGroupIndexMap& joint_name_group_index_map)
64 {
65  const auto& subgroup_joint_names =
66  robot_state->getJointModelGroup(servo_params.active_subgroup)->getActiveJointModelNames();
67 
68  // Create
69  Eigen::VectorXd move_group_delta_theta = Eigen::VectorXd::Zero(
70  robot_state->getJointModelGroup(servo_params.move_group_name)->getActiveJointModelNames().size());
71  for (size_t index = 0; index < subgroup_joint_names.size(); index++)
72  {
73  move_group_delta_theta[joint_name_group_index_map.at(subgroup_joint_names.at(index))] = sub_group_deltas[index];
74  }
75  return move_group_delta_theta;
76 };
77 } // namespace
78 
79 namespace moveit_servo
80 {
81 
82 JointDeltaResult jointDeltaFromJointJog(const JointJogCommand& command, const moveit::core::RobotStatePtr& robot_state,
83  const servo::Params& servo_params,
84  const JointNameToMoveGroupIndexMap& joint_name_group_index_map)
85 {
86  // Find the target joint position based on the commanded joint velocity
88  const auto& group_name =
89  servo_params.active_subgroup.empty() ? servo_params.move_group_name : servo_params.active_subgroup;
90  const moveit::core::JointModelGroup* joint_model_group = robot_state->getJointModelGroup(group_name);
91  const auto joint_names = joint_model_group->getActiveJointModelNames();
92  Eigen::VectorXd joint_position_delta(joint_names.size());
93  Eigen::VectorXd velocities(joint_names.size());
94 
95  velocities.setZero();
96  bool names_valid = true;
97 
98  for (size_t i = 0; i < command.names.size(); ++i)
99  {
100  auto it = std::find(joint_names.begin(), joint_names.end(), command.names[i]);
101  if (it != std::end(joint_names))
102  {
103  velocities[std::distance(joint_names.begin(), it)] = command.velocities[i];
104  }
105  else
106  {
107  RCLCPP_WARN_STREAM(getLogger(), "Invalid joint name: " << command.names[i]);
108 
109  names_valid = false;
110  break;
111  }
112  }
113  const bool velocity_valid = isValidCommand(velocities);
114  if (names_valid && velocity_valid)
115  {
116  joint_position_delta = velocities * servo_params.publish_period;
117  if (servo_params.command_in_type == "unitless")
118  {
119  joint_position_delta *= servo_params.scale.joint;
120  }
121  }
122  else
123  {
124  status = StatusCode::INVALID;
125  if (!names_valid)
126  {
127  RCLCPP_WARN_STREAM(getLogger(),
128  "Invalid joint names in joint jog command. Either you're sending commands for a joint "
129  "that is not part of the move group or certain joints cannot be moved because a "
130  "subgroup is active and they are not part of it.");
131  }
132  if (!velocity_valid)
133  {
134  RCLCPP_WARN_STREAM(getLogger(), "Invalid velocity values in joint jog command");
135  }
136  }
137 
138  if (!servo_params.active_subgroup.empty() && servo_params.active_subgroup != servo_params.move_group_name)
139  {
140  return std::make_pair(status, createMoveGroupDelta(joint_position_delta, robot_state, servo_params,
141  joint_name_group_index_map));
142  }
143 
144  return std::make_pair(status, joint_position_delta);
145 }
146 
147 JointDeltaResult jointDeltaFromTwist(const TwistCommand& command, const moveit::core::RobotStatePtr& robot_state,
148  const servo::Params& servo_params, const std::string& planning_frame,
149  const JointNameToMoveGroupIndexMap& joint_name_group_index_map)
150 {
152  const int num_joints =
153  robot_state->getJointModelGroup(servo_params.move_group_name)->getActiveJointModelNames().size();
154  Eigen::VectorXd joint_position_delta(num_joints);
155  Eigen::Vector<double, 6> cartesian_position_delta;
156 
157  const bool valid_command = isValidCommand(command);
158  const bool is_planning_frame = (command.frame_id == planning_frame);
159  const bool is_zero = command.velocities.isZero();
160  if (!is_zero && is_planning_frame && valid_command)
161  {
162  // Compute the Cartesian position delta based on incoming twist command.
163  cartesian_position_delta = command.velocities * servo_params.publish_period;
164  // This scaling is supposed to be applied to the command.
165  // But since it is only used here, we avoid creating a copy of the command,
166  // by applying the scaling to the computed Cartesian delta instead.
167  if (servo_params.command_in_type == "unitless")
168  {
169  cartesian_position_delta.head<3>() *= servo_params.scale.linear;
170  cartesian_position_delta.tail<3>() *= servo_params.scale.rotational;
171  }
172  else if (servo_params.command_in_type == "speed_units")
173  {
174  if (servo_params.scale.linear > 0.0)
175  {
176  const auto linear_speed_scale = command.velocities.head<3>().norm() / servo_params.scale.linear;
177  if (linear_speed_scale > 1.0)
178  {
179  cartesian_position_delta.head<3>() /= linear_speed_scale;
180  }
181  }
182  if (servo_params.scale.rotational > 0.0)
183  {
184  const auto angular_speed_scale = command.velocities.tail<3>().norm() / servo_params.scale.rotational;
185  if (angular_speed_scale > 1.0)
186  {
187  cartesian_position_delta.tail<3>() /= angular_speed_scale;
188  }
189  }
190  }
191 
192  // Compute the required change in joint angles.
193  const auto delta_result =
194  jointDeltaFromIK(cartesian_position_delta, robot_state, servo_params, joint_name_group_index_map);
195  status = delta_result.first;
196  if (status != StatusCode::INVALID)
197  {
198  joint_position_delta = delta_result.second;
199  // Get velocity scaling information for singularity.
200  const auto singularity_scaling_info =
201  velocityScalingFactorForSingularity(robot_state, cartesian_position_delta, servo_params);
202  // Apply velocity scaling for singularity, if there was any scaling.
203  if (singularity_scaling_info.second != StatusCode::NO_WARNING)
204  {
205  status = singularity_scaling_info.second;
206  RCLCPP_WARN_STREAM(getLogger(), SERVO_STATUS_CODE_MAP.at(status));
207  joint_position_delta *= singularity_scaling_info.first;
208  }
209  }
210  }
211  else if (is_zero)
212  {
213  joint_position_delta.setZero();
214  }
215  else
216  {
217  status = StatusCode::INVALID;
218  if (!valid_command)
219  {
220  RCLCPP_ERROR_STREAM(getLogger(), "Invalid twist command.");
221  }
222  if (!is_planning_frame)
223  {
224  RCLCPP_ERROR_STREAM(getLogger(), "Command frame is: " << command.frame_id << ", expected: " << planning_frame);
225  }
226  }
227  return std::make_pair(status, joint_position_delta);
228 }
229 
230 JointDeltaResult jointDeltaFromPose(const PoseCommand& command, const moveit::core::RobotStatePtr& robot_state,
231  const servo::Params& servo_params, const std::string& planning_frame,
232  const std::string& ee_frame,
233  const JointNameToMoveGroupIndexMap& joint_name_group_index_map)
234 {
236  const int num_joints =
237  robot_state->getJointModelGroup(servo_params.move_group_name)->getActiveJointModelNames().size();
238  Eigen::VectorXd joint_position_delta(num_joints);
239 
240  const bool valid_command = isValidCommand(command);
241  const bool is_planning_frame = (command.frame_id == planning_frame);
242 
243  if (valid_command && is_planning_frame)
244  {
245  Eigen::Vector<double, 6> cartesian_position_delta;
246 
247  // Compute linear and angular change needed.
248  const Eigen::Isometry3d ee_pose{ robot_state->getGlobalLinkTransform(planning_frame).inverse() *
249  robot_state->getGlobalLinkTransform(ee_frame) };
250  const Eigen::Quaterniond q_current(ee_pose.rotation());
251  Eigen::Quaterniond q_target(command.pose.rotation());
252  Eigen::Vector3d translation_error = command.pose.translation() - ee_pose.translation();
253 
254  // Limit the commands by the maximum linear and angular speeds provided.
255  if (servo_params.scale.linear > 0.0)
256  {
257  const auto linear_speed_scale =
258  (translation_error.norm() / servo_params.publish_period) / servo_params.scale.linear;
259  if (linear_speed_scale > 1.0)
260  {
261  translation_error /= linear_speed_scale;
262  }
263  }
264  if (servo_params.scale.rotational > 0.0)
265  {
266  const auto angular_speed_scale =
267  (std::abs(q_target.angularDistance(q_current)) / servo_params.publish_period) / servo_params.scale.rotational;
268  if (angular_speed_scale > 1.0)
269  {
270  q_target = q_current.slerp(1.0 / angular_speed_scale, q_target);
271  }
272  }
273 
274  // Compute the Cartesian deltas from the velocity-scaled values.
275  const auto angle_axis_error = Eigen::AngleAxisd(q_target * q_current.inverse());
276  cartesian_position_delta.head<3>() = translation_error;
277  cartesian_position_delta.tail<3>() = angle_axis_error.axis() * angle_axis_error.angle();
278 
279  // Compute the required change in joint angles.
280  const auto delta_result =
281  jointDeltaFromIK(cartesian_position_delta, robot_state, servo_params, joint_name_group_index_map);
282  status = delta_result.first;
283  if (status != StatusCode::INVALID)
284  {
285  joint_position_delta = delta_result.second;
286  // Get velocity scaling information for singularity.
287  const auto singularity_scaling_info =
288  velocityScalingFactorForSingularity(robot_state, cartesian_position_delta, servo_params);
289  // Apply velocity scaling for singularity, if there was any scaling.
290  if (singularity_scaling_info.second != StatusCode::NO_WARNING)
291  {
292  status = singularity_scaling_info.second;
293  RCLCPP_WARN_STREAM(getLogger(), SERVO_STATUS_CODE_MAP.at(status));
294  joint_position_delta *= singularity_scaling_info.first;
295  }
296  }
297  }
298  else
299  {
300  status = StatusCode::INVALID;
301  if (!valid_command)
302  {
303  RCLCPP_WARN_STREAM(getLogger(), "Invalid pose command.");
304  }
305  if (!is_planning_frame)
306  {
307  RCLCPP_WARN_STREAM(getLogger(), "Command frame is: " << command.frame_id << " expected: " << planning_frame);
308  }
309  }
310  return std::make_pair(status, joint_position_delta);
311 }
312 
313 JointDeltaResult jointDeltaFromIK(const Eigen::VectorXd& cartesian_position_delta,
314  const moveit::core::RobotStatePtr& robot_state, const servo::Params& servo_params,
315  const JointNameToMoveGroupIndexMap& joint_name_group_index_map)
316 {
317  const auto& group_name =
318  servo_params.active_subgroup.empty() ? servo_params.move_group_name : servo_params.active_subgroup;
319  const moveit::core::JointModelGroup* joint_model_group = robot_state->getJointModelGroup(group_name);
320 
321  std::vector<double> current_joint_positions;
322  robot_state->copyJointGroupPositions(joint_model_group, current_joint_positions);
323 
324  Eigen::VectorXd delta_theta(current_joint_positions.size());
326 
327  const kinematics::KinematicsBaseConstPtr ik_solver = joint_model_group->getSolverInstance();
328  bool ik_solver_supports_group = true;
329  if (ik_solver)
330  {
331  ik_solver_supports_group = ik_solver->supportsGroup(joint_model_group);
332  if (!ik_solver_supports_group)
333  {
334  status = StatusCode::INVALID;
335  RCLCPP_ERROR_STREAM(getLogger(), "Loaded IK plugin does not support group " << joint_model_group->getName());
336  }
337  }
338 
339  if (ik_solver && ik_solver_supports_group)
340  {
341  const Eigen::Isometry3d base_to_tip_frame_transform =
342  robot_state->getGlobalLinkTransform(ik_solver->getBaseFrame()).inverse() *
343  robot_state->getGlobalLinkTransform(ik_solver->getTipFrame());
344 
345  const geometry_msgs::msg::Pose next_pose =
346  poseFromCartesianDelta(cartesian_position_delta, base_to_tip_frame_transform);
347 
348  // setup for IK call
349  std::vector<double> solution;
350  solution.reserve(current_joint_positions.size());
351  moveit_msgs::msg::MoveItErrorCodes err;
353  opts.return_approximate_solution = true;
354  if (ik_solver->searchPositionIK(next_pose, current_joint_positions, servo_params.publish_period / 2.0, solution,
355  err, opts))
356  {
357  // find the difference in joint positions that will get us to the desired pose
358  for (size_t i = 0; i < current_joint_positions.size(); ++i)
359  {
360  delta_theta[i] = solution.at(i) - current_joint_positions.at(i);
361  }
362  }
363  else
364  {
365  status = StatusCode::INVALID;
366  RCLCPP_WARN_STREAM(getLogger(), "Could not find IK solution for requested motion, got error code " << err.val);
367  }
368  }
369  else
370  {
371  // Robot does not have an IK solver, use inverse Jacobian to compute IK.
372  const Eigen::MatrixXd jacobian = robot_state->getJacobian(joint_model_group);
373  const Eigen::JacobiSVD<Eigen::MatrixXd> svd =
374  Eigen::JacobiSVD<Eigen::MatrixXd>(jacobian, Eigen::ComputeThinU | Eigen::ComputeThinV);
375  const Eigen::MatrixXd matrix_s = svd.singularValues().asDiagonal();
376  const Eigen::MatrixXd pseudo_inverse = svd.matrixV() * matrix_s.inverse() * svd.matrixU().transpose();
377 
378  delta_theta = pseudo_inverse * cartesian_position_delta;
379  }
380 
381  if (!servo_params.active_subgroup.empty() && servo_params.active_subgroup != servo_params.move_group_name)
382  {
383  return std::make_pair(status,
384  createMoveGroupDelta(delta_theta, robot_state, servo_params, joint_name_group_index_map));
385  }
386 
387  return std::make_pair(status, delta_theta);
388 }
389 
390 } // namespace moveit_servo
const std::string & getName() const
Get the name of the joint group.
const kinematics::KinematicsBaseConstPtr getSolverInstance() const
const std::vector< std::string > & getActiveJointModelNames() const
Get the names of the active joints in this group. These are the names of the joints returned by getJo...
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.hpp:89
JointDeltaResult jointDeltaFromTwist(const TwistCommand &command, const moveit::core::RobotStatePtr &robot_state, const servo::Params &servo_params, const std::string &planning_frame, const JointNameToMoveGroupIndexMap &joint_name_group_index_map)
Compute the change in joint position for the given twist command.
Definition: command.cpp:147
geometry_msgs::msg::Pose poseFromCartesianDelta(const Eigen::VectorXd &delta_x, const Eigen::Isometry3d &base_to_tip_frame_transform)
Create a pose message for the provided change in Cartesian position.
Definition: common.cpp:115
std::pair< double, StatusCode > velocityScalingFactorForSingularity(const moveit::core::RobotStatePtr &robot_state, const Eigen::VectorXd &target_delta_x, const servo::Params &servo_params)
Computes scaling factor for velocity when the robot is near a singularity.
Definition: common.cpp:282
JointDeltaResult jointDeltaFromJointJog(const JointJogCommand &command, const moveit::core::RobotStatePtr &robot_state, const servo::Params &servo_params, const JointNameToMoveGroupIndexMap &joint_name_group_index_map)
Compute the change in joint position for the given joint jog command.
Definition: command.cpp:82
bool isValidCommand(const Eigen::VectorXd &command)
Checks if a given VectorXd is a valid command.
Definition: common.cpp:87
JointDeltaResult jointDeltaFromIK(const Eigen::VectorXd &cartesian_position_delta, const moveit::core::RobotStatePtr &robot_state, const servo::Params &servo_params, const JointNameToMoveGroupIndexMap &joint_name_group_index_map)
Computes the required change in joint angles for given Cartesian change, using the robot's IK solver.
Definition: command.cpp:313
std::pair< StatusCode, Eigen::VectorXd > JointDeltaResult
Definition: datatypes.hpp:85
const std::unordered_map< StatusCode, std::string > SERVO_STATUS_CODE_MAP({ { StatusCode::INVALID, "Invalid" }, { StatusCode::NO_WARNING, "No warnings" }, { StatusCode::DECELERATE_FOR_APPROACHING_SINGULARITY, "Moving closer to a singularity, decelerating" }, { StatusCode::HALT_FOR_SINGULARITY, "Very close to a singularity, emergency stop" }, { StatusCode::DECELERATE_FOR_LEAVING_SINGULARITY, "Moving away from a singularity, decelerating" }, { StatusCode::DECELERATE_FOR_COLLISION, "Close to a collision, decelerating" }, { StatusCode::HALT_FOR_COLLISION, "Collision detected, emergency stop" }, { StatusCode::JOINT_BOUND, "Close to a joint bound (position or velocity), halting" } })
JointDeltaResult jointDeltaFromPose(const PoseCommand &command, const moveit::core::RobotStatePtr &robot_state, const servo::Params &servo_params, const std::string &planning_frame, const std::string &ee_frame, const JointNameToMoveGroupIndexMap &joint_name_group_index_map)
Compute the change in joint position for the given pose command.
Definition: command.cpp:230
std::unordered_map< std::string, std::size_t > JointNameToMoveGroupIndexMap
Definition: datatypes.hpp:134
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.hpp:59
A set of options for the kinematics solver.
std::vector< std::string > names
Definition: datatypes.hpp:90
std::vector< double > velocities
Definition: datatypes.hpp:91
Eigen::Isometry3d pose
Definition: datatypes.hpp:107
Eigen::Vector< double, 6 > velocities
Definition: datatypes.hpp:99