12 #include <Eigen/Dense>
27 std::string leader_arm_id;
28 std::string follower_arm_id;
30 std::vector<std::string> leader_joint_names;
31 std::vector<std::string> follower_joint_names;
48 get1dParam<double>(
"leader/contact_force_threshold", node_handle);
50 get1dParam<double>(
"follower/contact_force_threshold", node_handle);
52 leader_arm_id = get1dParam<std::string>(
"leader/arm_id", node_handle);
53 follower_arm_id = get1dParam<std::string>(
"follower/arm_id", node_handle);
55 leader_joint_names = getJointParams<std::string>(
"leader/joint_names", node_handle);
56 follower_joint_names = getJointParams<std::string>(
"follower/joint_names", node_handle);
60 << std::boolalpha <<
debug_);
66 }
catch (
const std::invalid_argument& ex) {
75 dynamic_reconfigure::Server<franka_example_controllers::teleop_paramConfig>>(
81 auto init_publisher = [&node_handle](
auto& publisher,
const auto&
topic) {
82 publisher.init(node_handle,
topic, 1);
84 publisher.msg_.name.resize(7);
85 publisher.msg_.position.resize(7);
86 publisher.msg_.velocity.resize(7);
87 publisher.msg_.effort.resize(7);
97 auto get_marker = [](
const std::string&
arm_id, int32_t id,
const std::string& text) {
98 visualization_msgs::Marker marker;
99 marker.header.frame_id =
arm_id +
"_link0";
101 marker.ns =
"basic_shapes";
103 marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
104 marker.action = visualization_msgs::Marker::ADD;
106 marker.pose.position.x = 0.0;
107 marker.pose.position.y = 0.0;
108 marker.pose.position.z = 1.0;
109 marker.pose.orientation.x = 0.0;
110 marker.pose.orientation.y = 0.0;
111 marker.pose.orientation.z = 0.0;
112 marker.pose.orientation.w = 1.0;
116 marker.scale.x = 0.3;
117 marker.scale.y = 0.3;
118 marker.scale.z = 0.1;
120 marker.color.r = 0.0f;
121 marker.color.g = 1.0f;
122 marker.color.b = 0.0f;
123 marker.color.a = 1.0;
128 std::lock_guard<realtime_tools::RealtimePublisher<visualization_msgs::MarkerArray>> lock(
130 marker_pub_.
msg_.markers.push_back(get_marker(leader_arm_id, 1,
"leader"));
131 marker_pub_.
msg_.markers.push_back(get_marker(follower_arm_id, 2,
"follower"));
142 const std::string& arm_id,
143 const std::vector<std::string>& joint_names) {
145 if (not effort_joint_interface) {
147 ": Error getting effort joint interface from hardware of " +
157 ": Exception getting joint handle: " + std::string(e.
what()));
163 if (not state_interface) {
164 throw std::invalid_argument(
kControllerName +
": Error getting state interface from hardware.");
168 arm_data.
state_handle = std::make_unique<franka_hw::FrankaStateHandle>(
169 state_interface->getHandle(
arm_id +
"_robot"));
171 throw std::invalid_argument(
173 ": Exception getting state handle from interface: " + std::string(ex.
what()));
178 const std::array<double, 7> kPDZoneWidth = {{0.12, 0.09, 0.09, 0.09, 0.0349, 0.0349, 0.0349}};
179 const std::array<double, 7> kDZoneWidth = {{0.12, 0.09, 0.09, 0.09, 0.0349, 0.0349, 0.0349}};
180 const std::array<double, 7> kPDZoneStiffness = {
181 {2000.0, 2000.0, 1000.0, 1000.0, 500.0, 200.0, 200.0}};
182 const std::array<double, 7> kPDZoneDamping = {{30.0, 30.0, 30.0, 10.0, 5.0, 5.0, 5.0}};
183 const std::array<double, 7> kDZoneDamping = {{30.0, 30.0, 30.0, 10.0, 5.0, 5.0, 5.0}};
185 std::array<double, 7> upper_joint_soft_limit;
186 std::array<double, 7> lower_joint_soft_limit;
190 upper_joint_soft_limit, lower_joint_soft_limit, kPDZoneWidth, kDZoneWidth, kPDZoneStiffness,
191 kPDZoneDamping, kDZoneDamping);
201 q_target_last_ = Eigen::Map<Vector7d>(follower_robot_state.q.data());
208 init_leader_q_ = Eigen::Map<Vector7d>(leader_robot_state.q.data());
219 leader_data_.
q = Eigen::Map<Vector7d>(leader_robot_state.q.data());
220 leader_data_.
dq = Eigen::Map<Vector7d>(leader_robot_state.dq.data());
221 follower_data_.
q = Eigen::Map<Vector7d>(follower_robot_state.q.data());
235 Vector6d leader_f_ext_hat = Eigen::Map<Vector6d>(leader_robot_state.K_F_ext_hat_K.data());
241 Vector6d follower_f_ext_hat = Eigen::Map<Vector6d>(follower_robot_state.K_F_ext_hat_K.data());
263 for (
size_t i = 0; i < 7; ++i) {
278 if (!leader_robot_state.current_errors && !follower_robot_state.current_errors) {
292 Eigen::Map<Vector7d>(follower_robot_state.tau_ext_hat_filtered.data());
299 (-follower_tau_ext_hat);
316 auto to_eigen = [](
const std::array<double, 7>& data) {
return Vector7d(data.data()); };
317 auto from_eigen = [](
const Vector7d& data) {
318 return std::array<double, 7>{data(0), data(1), data(2), data(3), data(4), data(5), data(6)};
323 std::array<double, 7> virtual_wall_tau_follower =
346 for (
size_t i = 0; i < 7; ++i) {
355 const double delta_t) {
357 for (
size_t i = 0; i < 7; i++) {
358 double delta_x_max = dx_max[i] * delta_t;
359 double diff = x_calc[i] - x_last[i];
360 double x_saturated = x_last[i] + std::max(std::min(diff, delta_x_max), -delta_x_max);
361 x_limited[i] = std::max(std::min(x_saturated, x_max[i]), -x_max[i]);
367 const double neg_x_asymptote,
368 const double pos_x_asymptote,
369 const double shift_along_x,
370 const double increase_factor) {
372 0.5 * (pos_x_asymptote + neg_x_asymptote -
373 (pos_x_asymptote - neg_x_asymptote) * tanh(increase_factor * (
x - shift_along_x)));
378 franka_example_controllers::teleop_paramConfig& config,
426 const std::vector<std::string>& joint_names,
427 std::array<double, 7>& upper_joint_soft_limit,
428 std::array<double, 7>& lower_joint_soft_limit) {
430 std::size_t found = node_namespace.find_last_of(
'/');
431 std::string parent_namespace = node_namespace.substr(0, found);
433 if (!nh.
hasParam(parent_namespace +
"/robot_description")) {
434 throw std::invalid_argument(
kControllerName +
": No parameter robot_description (namespace: " +
435 parent_namespace +
")found to set joint limits!");
441 ": Could not initialize urdf model from robot_description "
443 parent_namespace +
").");
448 auto urdf_joint = urdf_model.getJoint(joint_name);
451 ": Could not get joint " << joint_name <<
" from urdf");
453 if (!urdf_joint->safety) {
461 << joint_name <<
" for joint limit interfaces");
468 for (
size_t i = 0; i < 7; ++i) {
480 for (
size_t i = 0; i < 7; ++i) {
506 auto buffer = getJointParams<double>(param_name, nh);
507 return Vector7d(Eigen::Map<Vector7d>(buffer.data()));
511 auto simple_ramp = [](
const double min,
const double max,
const double value) ->
double {
518 return (value -
min) / (max -
min);
521 for (
size_t i = 0; i < 7; ++i) {