Skip to content

Commit

Permalink
Include parameters header file
Browse files Browse the repository at this point in the history
  • Loading branch information
Abishalini committed Oct 28, 2022
1 parent 1ce69f0 commit 5e8c154
Show file tree
Hide file tree
Showing 4 changed files with 9 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
// ROS
#include <rclcpp/rclcpp.hpp>
#include <random_numbers/random_numbers.h>
#include <kdl_kinematics_parameters.hpp>

// ROS msgs
#include <geometry_msgs/msg/pose_stamped.hpp>
Expand Down Expand Up @@ -182,5 +183,8 @@ class KDLKinematicsPlugin : public kinematics::KinematicsBase
* > 1.0: orientation has more importance than position
* = 0.0: perform position-only IK */
double orientation_vs_position_weight_;

// std::shared_ptr<kdl_kinematics::ParamListener> param_listener_;
// kdl_kinematics::Params params_;
};
} // namespace kdl_kinematics_plugin
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,10 @@ kdl_kinematics:
orientation_vs_position: {
type: double,
default_value: 1.0,
description: "orientation vs position weight",
description: "Weight of orientation error vs position error
* < 1.0: orientation has less importance than position
* > 1.0: orientation has more importance than position
* = 0.0: perform position-only IK",
# validation:
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,6 @@
#include <moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h>
#include <moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.hpp>

#include "kdl_kinematics_parameters.hpp"

#include <tf2_kdl/tf2_kdl.hpp>
#include <tf2/transform_datatypes.h>

Expand Down
1 change: 1 addition & 0 deletions moveit_kinematics/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
<depend>moveit_core</depend>
<depend>class_loader</depend>
<depend>pluginlib</depend>
<depend>generate_parameter_library</depend>
<depend>eigen</depend>
<depend>tf2</depend>
<depend>tf2_kdl</depend>
Expand Down

0 comments on commit 5e8c154

Please # to comment.