9 #include <urdf_model/model.h> 17 #include <Eigen/Geometry> 32 MoveItOPWKinematicsPlugin::MoveItOPWKinematicsPlugin() : active_(false)
37 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
38 double search_discretization)
44 setValues(robot_description, group_name, base_frame, tip_frames, search_discretization);
48 const urdf::ModelInterfaceSharedPtr& urdf_model = rdf_loader.
getURDF();
50 if (!urdf_model || !srdf)
52 ROS_ERROR_NAMED(
"opw",
"URDF and SRDF must be loaded for OPW kinematics " 57 robot_model_.reset(
new robot_model::RobotModel(urdf_model, srdf));
65 std::cout << std::endl
66 <<
"Joint Model Variable Names: " 67 "------------------------------------------- " 70 std::copy(jm_names.begin(), jm_names.end(), std::ostream_iterator<std::string>(std::cout,
"\n"));
71 std::cout << std::endl;
94 for (std::size_t i = 0; i <
tip_frames_.size(); ++i)
107 <<
"/kinematics_solver_service_name");
108 std::string ik_service_name;
109 lookupParam(
"kinematics_solver_service_name", ik_service_name, std::string(
"solve_ik"));
130 ROS_DEBUG_NAMED(
"opw",
"ROS service-based kinematics solver initialized");
162 for (
unsigned int i = 0; i <
ik_group_info_.joint_names.size(); i++)
177 const std::vector<double> joint_angles = { 0.1, -0.1, 0.2, -0.3, 0.5, -0.8 };
184 fk_pose_moveit = base.inverse() * fk_pose_moveit;
200 auto Ra = Ta.rotation();
201 auto Rb = Tb.rotation();
202 for (
int i = 0; i < Ra.rows(); ++i)
204 for (
int j = 0; j < Ra.cols(); ++j)
206 if (std::abs(Ra(i, j) - Rb(i, j)) >
TOLERANCE)
208 ROS_ERROR_NAMED(
"opw",
"Pose orientation error on element (%d, %d).", i, j);
215 auto pa = Ta.translation();
216 auto pb = Tb.translation();
217 for (
int i = 0; i < 3; ++i)
219 if (std::abs(pa(i) - pb(i)) > TOLERANCE)
230 const std::vector<double>& ik_seed_state, std::vector<double>& solution,
231 moveit_msgs::MoveItErrorCodes& error_code,
235 std::vector<double> consistency_limits;
238 consistency_limits, options);
242 const std::vector<double>& ik_seed_state,
double timeout,
243 std::vector<double>& solution,
244 moveit_msgs::MoveItErrorCodes& error_code,
248 std::vector<double> consistency_limits;
250 return searchPositionIK(ik_pose, ik_seed_state, timeout, solution, solution_callback, error_code, consistency_limits,
255 const std::vector<double>& ik_seed_state,
double timeout,
256 const std::vector<double>& consistency_limits,
257 std::vector<double>& solution,
258 moveit_msgs::MoveItErrorCodes& error_code,
262 return searchPositionIK(ik_pose, ik_seed_state, timeout, solution, solution_callback, error_code, consistency_limits,
267 const std::vector<double>& ik_seed_state,
double timeout,
268 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
269 moveit_msgs::MoveItErrorCodes& error_code,
272 std::vector<double> consistency_limits;
273 return searchPositionIK(ik_pose, ik_seed_state, timeout, solution, solution_callback, error_code, consistency_limits,
278 const std::vector<double>& ik_seed_state,
double timeout,
279 const std::vector<double>& consistency_limits,
280 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
281 moveit_msgs::MoveItErrorCodes& error_code,
284 return searchPositionIK(ik_pose, ik_seed_state, timeout, solution, solution_callback, error_code, consistency_limits,
289 const std::vector<double>& ik_seed_state,
double timeout,
290 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
291 moveit_msgs::MoveItErrorCodes& error_code,
292 const std::vector<double>& consistency_limits,
296 std::vector<geometry_msgs::Pose> ik_poses;
297 ik_poses.push_back(ik_pose);
299 return searchPositionIK(ik_poses, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code,
304 const std::vector<double>& ik_seed_state,
double ,
305 const std::vector<double>& ,
306 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
307 moveit_msgs::MoveItErrorCodes& error_code,
314 error_code.val = error_code.NO_IK_SOLUTION;
322 "Seed state must have size " <<
dimension_ <<
" instead of size " << ik_seed_state.size());
323 error_code.val = error_code.NO_IK_SOLUTION;
330 ROS_ERROR_STREAM_NAMED(
"opw",
"Mismatched number of pose requests (" << ik_poses.size() <<
") to tip frames (" 332 <<
") in searchPositionIK");
333 error_code.val = error_code.NO_IK_SOLUTION;
337 Eigen::Affine3d pose;
339 std::vector<std::vector<double>> solutions;
343 error_code.val = error_code.NO_IK_SOLUTION;
347 std::vector<LimitObeyingSol> limit_obeying_solutions;
349 for (
auto& sol : solutions)
358 limit_obeying_solutions.push_back({ sol,
distance(sol, ik_seed_state) });
361 if (limit_obeying_solutions.empty())
363 ROS_DEBUG_NAMED(
"opw",
"None of the solutions is within joint limits");
370 std::sort(limit_obeying_solutions.begin(), limit_obeying_solutions.end());
372 if (!solution_callback)
374 solution = limit_obeying_solutions.front().value;
378 for (
auto& sol : limit_obeying_solutions)
380 solution_callback(ik_poses[0], sol.value, error_code);
381 if (error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
383 solution = sol.value;
394 const std::vector<double>& ,
398 if (ik_poses.size() > 1 || ik_poses.size() == 0)
403 Eigen::Affine3d pose;
409 const std::vector<double>& joint_angles,
410 std::vector<geometry_msgs::Pose>& poses)
const 417 poses.resize(link_names.size());
427 ROS_ERROR_STREAM_NAMED(
"opw",
"Mismatched number of pose requests (" << poses.size() <<
") to tip frames (" 429 <<
") in searchPositionFK");
457 ROS_INFO_STREAM(
"Getting kinematic parameters from parameter server.");
461 std::map<std::string, double> geometric_parameters;
462 if (!
lookupParam(
"opw_kinematics_geometric_parameters", geometric_parameters, {}))
468 std::vector<double> joint_offsets;
469 if (!
lookupParam(
"opw_kinematics_joint_offsets", joint_offsets, {}))
475 std::vector<int> joint_sign_corrections;
476 if (!
lookupParam(
"opw_kinematics_joint_sign_corrections", joint_sign_corrections, {}))
490 if (joint_offsets.size() != 6)
492 ROS_ERROR_STREAM(
"Expected joint_offsets to contain 6 elements, but it has " << joint_offsets.size() <<
".");
496 if (joint_sign_corrections.size() != 6)
498 ROS_ERROR_STREAM(
"Expected joint_sign_corrections to contain 6 elements, but it has " 499 << joint_sign_corrections.size() <<
".");
503 for (std::size_t i = 0; i < joint_offsets.size(); ++i)
517 for (
size_t i = 0; i < a.size(); ++i)
518 cost += std::abs(b[i] - a[i]);
524 const std::vector<std::vector<double>>& candidates)
527 double lowest_cost = std::numeric_limits<double>::max();
528 for (
size_t i = 0; i < candidates.size(); ++i)
530 assert(target.size() == candidates[i].size());
531 double c =
distance(target, candidates[i]);
542 std::vector<std::vector<double>>& joint_poses)
const 553 Eigen::Isometry3d pose_isometry;
554 pose_isometry = pose.matrix();
556 std::array<double, 6 * 8> sols;
560 std::vector<double> tmp(6);
561 for (
int i = 0; i < 8; i++)
563 double* sol = sols.data() + 6 * i;
569 std::copy(sol, sol + 6, tmp.data());
572 joint_poses.push_back(tmp);
577 return joint_poses.size() > 0;
581 std::vector<double>& joint_pose)
const 584 std::vector<std::vector<double>> joint_poses;
std::vector< unsigned int > redundant_joint_indices_
static std::size_t closestJointPose(const std::vector< double > &target, const std::vector< std::vector< double >> &candidates)
const std::vector< std::string > & getJointNames() const override
Return all the joint names in the order they are used internally.
bool selfTest()
check forward and inverse kinematics consistency
bool comparePoses(Eigen::Isometry3d &Ta, Eigen::Affine3d &Tb)
check if two poses are the same within an absolute tolerance of 1e-6
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
bool getIK(const Eigen::Affine3d &pose, const std::vector< double > &seed_state, std::vector< double > &joint_pose) const
virtual bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const override
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
const srdf::ModelSharedPtr & getSRDF() const
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
std::vector< std::string > tip_frames_
int num_possible_redundant_joints_
#define ROS_INFO_STREAM_NAMED(name, args)
robot_state::RobotStatePtr robot_state_
moveit_msgs::KinematicSolverInfo ik_group_info_
virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
bool isValid(const T *qs)
void harmonizeTowardZero(T *qs)
virtual bool getPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
#define ROS_DEBUG_NAMED(name,...)
virtual bool initialize(const std::string &robot_description, const std::string &group_name, const std::string &base_name, const std::string &tip_frame, double search_discretization) override
bool getAllIK(const Eigen::Affine3d &pose, std::vector< std::vector< double >> &joint_poses) const
Specific implementation of kinematics using ROS service calls to communicate with external IK solvers...
bool isRedundantJoint(unsigned int index) const
robot_model::JointModelGroup * joint_model_group_
signed char sign_corrections[6]
virtual void setValues(const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization)
static double distance(const std::vector< double > &a, const std::vector< double > &b)
bool lookupParam(const std::string ¶m, T &val, const T &default_val) const
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
robot_model::RobotModelPtr robot_model_
#define ROS_INFO_STREAM(args)
virtual bool setRedundantJoints(const std::vector< unsigned int > &redundant_joint_indices) override
#define ROS_ERROR_NAMED(name,...)
bool timedOut(const ros::WallTime &start_time, double duration) const
int getJointIndex(const std::string &name) const
#define ROS_ERROR_STREAM(args)
opw_kinematics::Parameters< double > opw_parameters_
const std::vector< std::string > & getVariableNames() const
Return all the variable names in the order they are represented internally.
void inverse(const Parameters< T > ¶ms, const Transform< T > &pose, T *out) noexcept
Computes up to 8 kinematically unique joint solutions that put the tool flange of the robot described...
std::string robot_description_
Transform< T > forward(const Parameters< T > &p, const T *qs) noexcept
Computes the tool pose of the robot described by when said robot has the joint positions given by qs...
CLASS_LOADER_REGISTER_CLASS(Dog, Base)
const urdf::ModelInterfaceSharedPtr & getURDF() const