40 #include <kdl/jntarray.hpp>
42 #include <kdl/tree.hpp>
48 inline geometry_msgs::Vector3 transformVector(
const Eigen::Isometry3d& transform,
const geometry_msgs::Vector3& vector)
55 geometry_msgs::Vector3 result;
65 const geometry_msgs::Vector3& gravity_vector)
74 ROS_ERROR_NAMED(
"dynamics_solver",
"Group '%s' is not a chain. Will not initialize dynamics solver",
82 ROS_ERROR_NAMED(
"dynamics_solver",
"Group '%s' has a mimic joint. Will not initialize dynamics solver",
91 ROS_ERROR_NAMED(
"dynamics_solver",
"Group '%s' does not have a parent link", group_name.c_str());
101 const urdf::ModelInterfaceSharedPtr urdf_model =
robot_model_->getURDF();
107 ROS_ERROR_NAMED(
"dynamics_solver",
"Could not initialize tree object");
113 ROS_ERROR_NAMED(
"dynamics_solver",
"Could not initialize chain object");
121 state_->setToDefaultValues();
124 for (
const std::string& joint_model_name : joint_model_names)
126 const urdf::Joint* ujoint = urdf_model->getJoint(joint_model_name).get();
127 if (ujoint && ujoint->limits)
133 KDL::Vector gravity(gravity_vector.x, gravity_vector.y,
142 const std::vector<double>& joint_accelerations,
143 const std::vector<geometry_msgs::Wrench>& wrenches, std::vector<double>& torques)
const
147 ROS_DEBUG_NAMED(
"dynamics_solver",
"Did not construct DynamicsSolver object properly. "
148 "Check error logs.");
183 kdl_angles(i) = joint_angles[i];
184 kdl_velocities(i) = joint_velocities[i];
185 kdl_accelerations(i) = joint_accelerations[i];
190 kdl_wrenches[i](0) = wrenches[i].force.x;
191 kdl_wrenches[i](1) = wrenches[i].force.y;
192 kdl_wrenches[i](2) = wrenches[i].force.z;
194 kdl_wrenches[i](3) = wrenches[i].torque.x;
195 kdl_wrenches[i](4) = wrenches[i].torque.y;
196 kdl_wrenches[i](5) = wrenches[i].torque.z;
199 if (
chain_id_solver_->CartToJnt(kdl_angles, kdl_velocities, kdl_accelerations, kdl_wrenches, kdl_torques) < 0)
201 ROS_ERROR_NAMED(
"dynamics_solver",
"Something went wrong computing torques");
206 torques[i] = kdl_torques(i);
212 unsigned int& joint_saturated)
const
216 ROS_DEBUG_NAMED(
"dynamics_solver",
"Did not construct DynamicsSolver object properly. "
217 "Check error logs.");
229 if (!
getTorques(joint_angles, joint_velocities, joint_accelerations, wrenches, zero_torques))
244 const Eigen::Isometry3d& tip_frame =
state_->getFrameTransform(
tip_name_);
245 Eigen::Isometry3d
transform = tip_frame.inverse() * base_frame;
246 wrenches.back().force.z = 1.0;
247 wrenches.back().force = transformVector(transform, wrenches.back().force);
248 wrenches.back().torque = transformVector(transform, wrenches.back().torque);
250 ROS_DEBUG_NAMED(
"dynamics_solver",
"New wrench (local frame): %f %f %f", wrenches.back().force.x,
251 wrenches.back().force.y, wrenches.back().force.z);
253 if (!
getTorques(joint_angles, joint_velocities, joint_accelerations, wrenches, torques))
256 double min_payload = std::numeric_limits<double>::max();
259 double payload_joint = std::max<double>((
max_torques_[i] - zero_torques[i]) / (torques[i] - zero_torques[i]),
261 (torques[i] - zero_torques[i]));
262 ROS_DEBUG_NAMED(
"dynamics_solver",
"Joint: %d, Actual Torque: %f, Max Allowed: %f, Gravity: %f", i, torques[i],
264 ROS_DEBUG_NAMED(
"dynamics_solver",
"Joint: %d, Payload Allowed (N): %f", i, payload_joint);
265 if (payload_joint < min_payload)
267 min_payload = payload_joint;
277 std::vector<double>& joint_torques)
const
281 ROS_DEBUG_NAMED(
"dynamics_solver",
"Did not construct DynamicsSolver object properly. "
282 "Check error logs.");
299 const Eigen::Isometry3d& base_frame =
state_->getFrameTransform(
base_name_);
300 const Eigen::Isometry3d& tip_frame =
state_->getFrameTransform(
tip_name_);
301 Eigen::Isometry3d
transform = tip_frame.inverse() * base_frame;
302 wrenches.back().force.z = payload *
gravity_;
303 wrenches.back().force = transformVector(transform, wrenches.back().force);
304 wrenches.back().torque = transformVector(transform, wrenches.back().torque);
306 ROS_DEBUG_NAMED(
"dynamics_solver",
"New wrench (local frame): %f %f %f", wrenches.back().force.x,
307 wrenches.back().force.y, wrenches.back().force.z);
309 return getTorques(joint_angles, joint_velocities, joint_accelerations, wrenches, joint_torques);