iterative_torque_limit_parameterization.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2023, Re:Build AppliedLogix, 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 /* Author: Andy Zelenak */
35 
38 
39 namespace trajectory_processing
40 {
41 namespace
42 {
43 const std::string LOGNAME = "trajectory_processing.iterative_torque_limit_parameterization";
44 }
45 
47  const double resample_dt,
48  const double min_angle_change)
49  : totg_(path_tolerance, resample_dt, min_angle_change)
50 {
51 }
52 
54  robot_trajectory::RobotTrajectory& trajectory, const geometry_msgs::Vector3& gravity_vector,
55  const std::vector<geometry_msgs::Wrench>& external_link_wrenches, const std::vector<double>& joint_torque_limits,
56  double accel_limit_decrement_factor, const std::unordered_map<std::string, double>& velocity_limits,
57  const std::unordered_map<std::string, double>& acceleration_limits, const double max_velocity_scaling_factor,
58  const double max_acceleration_scaling_factor) const
59 {
60  // 1. Call computeTimeStamps() to time-parameterize the trajectory with given vel/accel limits.
61  // 2. Run forward dynamics to check if torque limits are violated at any waypoint.
62  // 3. If a torque limit was violated, decrease the acceleration limit for that joint and go back to Step 1.
63 
64  if (trajectory.empty())
65  return true;
66 
67  const moveit::core::JointModelGroup* group = trajectory.getGroup();
68  if (!group)
69  {
70  ROS_ERROR_NAMED(LOGNAME, "It looks like the planner did not set the group the plan was computed for");
71  return false;
72  }
73 
74  // Create a mutable copy of acceleration_limits
75  std::unordered_map<std::string, double> mutable_accel_limits = acceleration_limits;
76 
77  size_t dof = group->getActiveJointModels().size();
78 
79  if (joint_torque_limits.size() != dof)
80  {
81  ROS_ERROR_STREAM_NAMED(LOGNAME, "Joint torque limit vector size (" << joint_torque_limits.size()
82  << ") does not match the DOF of the RobotModel ("
83  << dof << ")");
84  return false;
85  }
86 
87  if (accel_limit_decrement_factor < 0.01 || accel_limit_decrement_factor > 0.2)
88  {
89  ROS_ERROR_NAMED(LOGNAME, "The accel_limit_decrement_factor is outside the typical range [0.01, 0.2]");
90  return false;
91  }
92 
93  dynamics_solver::DynamicsSolver dynamics_solver(trajectory.getRobotModel(), group->getName(), gravity_vector);
94 
95  // Copy the waypoints so we can modify them while iterating
96  moveit_msgs::RobotTrajectory original_traj;
97  trajectory.getRobotTrajectoryMsg(original_traj);
98  moveit::core::RobotState initial_state = trajectory.getFirstWayPoint();
99 
100  bool iteration_needed = true;
101  size_t num_iterations = 0;
102  const size_t max_iterations = 10;
103 
104  while (iteration_needed && num_iterations < max_iterations)
105  {
106  ++num_iterations;
107  iteration_needed = false;
108 
109  totg_.computeTimeStamps(trajectory, velocity_limits, mutable_accel_limits, max_velocity_scaling_factor,
110  max_acceleration_scaling_factor);
111 
112  std::vector<double> joint_positions(dof);
113  std::vector<double> joint_velocities(dof);
114  std::vector<double> joint_accelerations(dof);
115  std::vector<double> joint_torques(dof);
116 
117  const std::vector<const moveit::core::JointModel*>& joint_models = group->getActiveJointModels();
118 
119  // Check if any torque limits are violated
120  for (size_t waypoint_idx = 0; waypoint_idx < trajectory.getWayPointCount(); ++waypoint_idx)
121  {
122  moveit::core::RobotStatePtr& waypoint = trajectory.getWayPointPtr(waypoint_idx);
123  waypoint->copyJointGroupPositions(group->getName(), joint_positions);
124  waypoint->copyJointGroupVelocities(group->getName(), joint_velocities);
125  waypoint->copyJointGroupAccelerations(group->getName(), joint_accelerations);
126 
127  if (!dynamics_solver.getTorques(joint_positions, joint_velocities, joint_accelerations, external_link_wrenches,
128  joint_torques))
129  {
130  ROS_ERROR_STREAM_NAMED(LOGNAME, "Dynamics computation failed.");
131  return false;
132  }
133 
134  // For each joint, check if torque exceeds the limit
135  for (size_t joint_idx = 0; joint_idx < joint_torque_limits.size(); ++joint_idx)
136  {
137  if (std::fabs(joint_torques.at(joint_idx)) > joint_torque_limits.at(joint_idx))
138  {
139  // We can't always just decrease acceleration to decrease joint torque.
140  // There are some edge cases where decreasing acceleration could actually increase joint torque. For example,
141  // if gravity is accelerating the joint. In that case, the joint would be fighting against gravity more.
142  // There is also a small chance that changing acceleration has no effect on joint torque, for example:
143  // centripetal acceleration caused by velocity of another joint. This should be uncommon on serial manipulators
144  // because their torque limits are high enough to withstand issues like that (or it just wouldn't work at all...)
145 
146  // Reset
147  waypoint->copyJointGroupAccelerations(group->getName(), joint_accelerations);
148 
149  // Check if decreasing acceleration of this joint actually decreases joint torque. Else, increase acceleration.
150  double previous_torque = joint_torques.at(joint_idx);
151  joint_accelerations.at(joint_idx) *= (1 + accel_limit_decrement_factor);
152  if (!dynamics_solver.getTorques(joint_positions, joint_velocities, joint_accelerations,
153  external_link_wrenches, joint_torques))
154  {
155  ROS_ERROR_STREAM_NAMED(LOGNAME, "Dynamics computation failed.");
156  return false;
157  }
158  if (std::fabs(joint_torques.at(joint_idx)) < std::fabs(previous_torque))
159  {
160  mutable_accel_limits.at(joint_models.at(joint_idx)->getName()) *= (1 + accel_limit_decrement_factor);
161  }
162  else
163  {
164  mutable_accel_limits.at(joint_models.at(joint_idx)->getName()) *= (1 - accel_limit_decrement_factor);
165  }
166 
167  mutable_accel_limits.at(joint_models.at(joint_idx)->getName()) *= (1 - accel_limit_decrement_factor);
168  iteration_needed = true;
169  }
170  } // for each joint
171  if (iteration_needed)
172  {
173  // Start over from the first waypoint
174  break;
175  }
176  } // for each waypoint
177 
178  if (iteration_needed)
179  {
180  // Reset
181  trajectory.setRobotTrajectoryMsg(initial_state, original_traj);
182  }
183  } // while (iteration_needed && num_iterations < max_iterations)
184 
185  return true;
186 }
187 } // namespace trajectory_processing
moveit::core::JointModelGroup::getActiveJointModels
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
Definition: joint_model_group.h:222
robot_trajectory::RobotTrajectory::getWayPointCount
std::size_t getWayPointCount() const
Definition: robot_trajectory.h:131
robot_trajectory::RobotTrajectory::getGroup
const moveit::core::JointModelGroup * getGroup() const
Definition: robot_trajectory.h:118
dynamics_solver::DynamicsSolver
Definition: dynamics_solver.h:91
robot_trajectory::RobotTrajectory::getRobotModel
const moveit::core::RobotModelConstPtr & getRobotModel() const
Definition: robot_trajectory.h:113
moveit::core::JointModelGroup
Definition: joint_model_group.h:134
trajectory_processing::IterativeTorqueLimitParameterization::computeTimeStampsWithTorqueLimits
bool computeTimeStampsWithTorqueLimits(robot_trajectory::RobotTrajectory &trajectory, const geometry_msgs::Vector3 &gravity_vector, const std::vector< geometry_msgs::Wrench > &external_link_wrenches, const std::vector< double > &joint_torque_limits, double accel_limit_decrement_factor, const std::unordered_map< std::string, double > &velocity_limits, const std::unordered_map< std::string, double > &acceleration_limits, const double max_velocity_scaling_factor, const double max_acceleration_scaling_factor) const
Compute a trajectory with waypoints spaced equally in time (according to resample_dt_)....
Definition: iterative_torque_limit_parameterization.cpp:84
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
moveit::core::RobotState
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:155
robot_trajectory::RobotTrajectory
Maintain a sequence of waypoints and the time durations between these waypoints.
Definition: robot_trajectory.h:84
robot_trajectory::RobotTrajectory::setRobotTrajectoryMsg
RobotTrajectory & setRobotTrajectoryMsg(const moveit::core::RobotState &reference_state, const trajectory_msgs::JointTrajectory &trajectory)
Copy the content of the trajectory message into this class. The trajectory message itself is not requ...
Definition: robot_trajectory.cpp:389
moveit::core::JointModelGroup::getName
const std::string & getName() const
Get the name of the joint group.
Definition: joint_model_group.h:185
robot_trajectory::RobotTrajectory::getRobotTrajectoryMsg
void getRobotTrajectoryMsg(moveit_msgs::RobotTrajectory &trajectory, const std::vector< std::string > &joint_filter=std::vector< std::string >()) const
Definition: robot_trajectory.cpp:255
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
robot_trajectory::RobotTrajectory::empty
bool empty() const
Definition: robot_trajectory.h:195
trajectory_processing
Definition: iterative_spline_parameterization.h:43
dynamics_solver
This namespace includes the dynamics_solver library.
Definition: dynamics_solver.h:50
trajectory_processing::IterativeTorqueLimitParameterization::IterativeTorqueLimitParameterization
IterativeTorqueLimitParameterization(const double path_tolerance=0.1, const double resample_dt=0.1, const double min_angle_change=0.001)
Definition: iterative_torque_limit_parameterization.cpp:77
robot_trajectory::RobotTrajectory::getFirstWayPoint
const moveit::core::RobotState & getFirstWayPoint() const
Definition: robot_trajectory.h:146
iterative_torque_limit_parameterization.h
trajectory_processing::TimeOptimalTrajectoryGeneration::computeTimeStamps
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
Compute a trajectory with waypoints spaced equally in time (according to resample_dt_)....
Definition: time_optimal_trajectory_generation.h:191
trajectory_processing::IterativeTorqueLimitParameterization::totg_
TimeOptimalTrajectoryGeneration totg_
Definition: iterative_torque_limit_parameterization.h:138
robot_trajectory::RobotTrajectory::getWayPointPtr
moveit::core::RobotStatePtr & getWayPointPtr(std::size_t index)
Definition: robot_trajectory.h:151
dynamics_solver.h
trajectory_processing::LOGNAME
const std::string LOGNAME
Definition: time_optimal_trajectory_generation.cpp:49


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sat Apr 27 2024 02:25:25