Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add approximate solution joint jump threshold parameter #42

Merged
merged 3 commits into from
May 5, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions include/pick_ik/fk_moveit.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include <memory>
#include <moveit/robot_model/joint_model_group.h>
#include <moveit/robot_model/robot_model.h>
#include <mutex>
#include <vector>

namespace pick_ik {
Expand All @@ -13,6 +14,7 @@ using FkFn = std::function<std::vector<Eigen::Isometry3d>(std::vector<double> co

auto make_fk_fn(std::shared_ptr<moveit::core::RobotModel const> robot_model,
moveit::core::JointModelGroup const* jmg,
std::mutex& mx,
std::vector<size_t> tip_link_indices) -> FkFn;

} // namespace pick_ik
7 changes: 4 additions & 3 deletions src/fk_moveit.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,14 +10,15 @@ namespace pick_ik {

auto make_fk_fn(std::shared_ptr<moveit::core::RobotModel const> robot_model,
moveit::core::JointModelGroup const* jmg,
std::mutex& mx,
std::vector<size_t> tip_link_indices) -> FkFn {
auto robot_state = moveit::core::RobotState(robot_model);
robot_state.setToDefaultValues();

// IK function is mutable so it re-uses the robot_state instead of creating
// new copies. This function should not be shared between threads.
// It is however safe to make copies of.
return [=](std::vector<double> const& active_positions) mutable {
// new copies. This function accepts a mutex so that it can be made thread-safe.
return [=, &mx](std::vector<double> const& active_positions) mutable {
std::scoped_lock lock(mx);
robot_state.setJointGroupPositions(jmg, active_positions);
robot_state.updateLinkTransforms();

Expand Down
4 changes: 2 additions & 2 deletions src/goal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,8 @@ auto make_frame_test_fn(Eigen::Isometry3d goal_frame,
auto const q_goal = Eigen::Quaterniond(goal_frame.rotation());
auto const q_frame = Eigen::Quaterniond(tip_frame.rotation());
auto const angular_distance = q_frame.angularDistance(q_goal);
return ((goal_frame.translation() - tip_frame.translation()).norm() <=
position_threshold) &&
auto const linear_distance = (goal_frame.translation() - tip_frame.translation()).norm();
return (linear_distance <= position_threshold) &&
(!orientation_threshold.has_value() ||
std::abs(angular_distance) <= orientation_threshold.value());
};
Expand Down
8 changes: 8 additions & 0 deletions src/pick_ik_parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,14 @@ pick_ik:
gt_eq<>: [0.0],
},
}
approximate_solution_joint_threshold: {
type: double,
default_value: 0.0,
description: "Joint threshold for approximate IK solutions, in radians. If displacement is larger than this, the approximate solution will fall back to the initial guess",
validation: {
gt_eq<>: [0.0],
},
}
cost_threshold: {
type: double,
default_value: 0.001,
Expand Down
25 changes: 20 additions & 5 deletions src/pick_ik_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,8 @@ class PickIKPlugin : public kinematics::KinematicsBase {
std::vector<size_t> tip_link_indices_;
Robot robot_;

mutable std::mutex fk_mutex_;

public:
virtual bool initialize(rclcpp::Node::SharedPtr const& node,
moveit::core::RobotModel const& robot_model,
Expand Down Expand Up @@ -127,7 +129,7 @@ class PickIKPlugin : public kinematics::KinematicsBase {
make_pose_cost_functions(goal_frames, params.rotation_scale);

// forward kinematics function
auto const fk_fn = make_fk_fn(robot_model_, jmg_, tip_link_indices_);
auto const fk_fn = make_fk_fn(robot_model_, jmg_, fk_mutex_, tip_link_indices_);

// Create goals (weighted cost functions)
auto goals = std::vector<Goal>{};
Expand Down Expand Up @@ -209,10 +211,11 @@ class PickIKPlugin : public kinematics::KinematicsBase {
solution = ik_seed_state;
}

// If using an approximate solution, check against the maximum allowable pose threshold.
// If the approximate solution is too far from the goal frame, fall back to the initial
// state.
// If using an approximate solution, check against the maximum allowable pose and joint
// thresholds. If the approximate solution is too far from the goal frame,
// fall back to the initial state.
if (options.return_approximate_solution) {
// Check pose thresholds
std::optional<double> approximate_solution_orientation_threshold = std::nullopt;
if (test_rotation) {
approximate_solution_orientation_threshold =
Expand All @@ -230,6 +233,18 @@ class PickIKPlugin : public kinematics::KinematicsBase {
break;
}
}

// Check joint thresholds
if (approx_solution_valid && params.approximate_solution_joint_threshold > 0.0) {
for (size_t i = 0; i < solution.size(); ++i) {
if (std::abs(solution[i] - ik_seed_state[i]) >
params.approximate_solution_joint_threshold) {
approx_solution_valid = false;
break;
}
}
}

if (!approx_solution_valid) {
error_code.val = error_code.NO_IK_SOLUTION;
solution = ik_seed_state;
Expand All @@ -242,7 +257,7 @@ class PickIKPlugin : public kinematics::KinematicsBase {
solution_callback(ik_poses.front(), solution, error_code);
}

return error_code.val == error_code.SUCCESS;
return found_solution;
}

virtual std::vector<std::string> const& getJointNames() const { return joint_names_; }
Expand Down
1 change: 0 additions & 1 deletion src/robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@ auto Robot::from(std::shared_ptr<moveit::core::RobotModel const> const& model,
std::vector<size_t> tip_link_indices) -> Robot {
auto robot = Robot{};

// jmg_->getKinematicsSolverJointBijection();
auto const active_variable_indices = get_active_variable_indices(model, jmg, tip_link_indices);
auto const variable_count = active_variable_indices.size();

Expand Down
6 changes: 4 additions & 2 deletions tests/ik_memetic_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,8 @@ auto solve_memetic_ik_test(moveit::core::RobotModelPtr robot_model,
// Make forward kinematics function
auto const jmg = robot_model->getJointModelGroup(group_name);
auto const tip_link_indices = pick_ik::get_link_indices(robot_model, {goal_frame_name}).value();
auto const fk_fn = pick_ik::make_fk_fn(robot_model, jmg, tip_link_indices);
std::mutex mx;
auto const fk_fn = pick_ik::make_fk_fn(robot_model, jmg, mx, tip_link_indices);
auto const robot = pick_ik::Robot::from(robot_model, jmg, tip_link_indices);

// Make goal function(s)
Expand Down Expand Up @@ -93,7 +94,8 @@ TEST_CASE("Panda model Memetic IK") {

auto const jmg = robot_model->getJointModelGroup("panda_arm");
auto const tip_link_indices = pick_ik::get_link_indices(robot_model, {"panda_hand"}).value();
auto const fk_fn = pick_ik::make_fk_fn(robot_model, jmg, tip_link_indices);
std::mutex mx;
auto const fk_fn = pick_ik::make_fk_fn(robot_model, jmg, mx, tip_link_indices);

std::vector<double> const home_joint_angles =
{0.0, -M_PI_4, 0.0, -3.0 * M_PI_4, 0.0, M_PI_2, M_PI_4};
Expand Down
9 changes: 6 additions & 3 deletions tests/ik_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,8 @@ TEST_CASE("RR model FK") {
auto const jmg = robot_model->getJointModelGroup("group");
auto const tip_link_indices = pick_ik::get_link_indices(robot_model, {"ee"}).value();

auto const fk_fn = pick_ik::make_fk_fn(robot_model, jmg, tip_link_indices);
std::mutex mx;
auto const fk_fn = pick_ik::make_fk_fn(robot_model, jmg, mx, tip_link_indices);

SECTION("Zero joint position") {
std::vector<double> const joint_vals = {0.0, 0.0};
Expand Down Expand Up @@ -93,7 +94,8 @@ auto solve_ik_test(moveit::core::RobotModelPtr robot_model,
// Make forward kinematics function
auto const jmg = robot_model->getJointModelGroup(group_name);
auto const tip_link_indices = pick_ik::get_link_indices(robot_model, {goal_frame_name}).value();
auto const fk_fn = pick_ik::make_fk_fn(robot_model, jmg, tip_link_indices);
std::mutex mx;
auto const fk_fn = pick_ik::make_fk_fn(robot_model, jmg, mx, tip_link_indices);

// Make solution function
auto const test_rotation = (params.rotation_scale > 0.0);
Expand Down Expand Up @@ -234,7 +236,8 @@ TEST_CASE("Panda model IK") {

auto const jmg = robot_model->getJointModelGroup("panda_arm");
auto const tip_link_indices = pick_ik::get_link_indices(robot_model, {"panda_hand"}).value();
auto const fk_fn = pick_ik::make_fk_fn(robot_model, jmg, tip_link_indices);
std::mutex mx;
auto const fk_fn = pick_ik::make_fk_fn(robot_model, jmg, mx, tip_link_indices);

std::vector<double> const home_joint_angles =
{0.0, -M_PI_4, 0.0, -3.0 * M_PI_4, 0.0, M_PI_2, M_PI_4};
Expand Down
Loading