teleop_joint_pd_example_controller.h
Go to the documentation of this file.
1 // Copyright (c) 2020 Franka Emika GmbH
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
3 #pragma once
4 
6 #include <franka_example_controllers/teleop_paramConfig.h>
9 
10 #include <control_msgs/GripperCommandAction.h>
12 #include <dynamic_reconfigure/server.h>
16 #include <ros/ros.h>
17 #include <sensor_msgs/JointState.h>
18 #include <std_msgs/Float64.h>
19 #include <visualization_msgs/MarkerArray.h>
20 
21 #include <Eigen/Dense>
22 #include <memory>
23 #include <mutex>
24 #include <vector>
25 
36 };
37 
49  hardware_interface::EffortJointInterface,
50  franka_hw::FrankaStateInterface> {
51  public:
59  bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& node_handle) override;
60 
65  void starting(const ros::Time& /*time*/) override;
66 
72  void update(const ros::Time& /*time*/, const ros::Duration& period) override;
73 
74  private:
75  using Vector6d = Eigen::Matrix<double, 6, 1>;
76  using Vector7d = Eigen::Matrix<double, 7, 1>;
77  using Matrix7d = Eigen::Matrix<double, 7, 7>;
78 
80  std::unique_ptr<franka_hw::FrankaStateHandle> state_handle;
81  std::vector<hardware_interface::JointHandle> joint_handles;
82 
83  // A virtual wall to avoid joint limits.
84  std::unique_ptr<JointWallContainer<7>> virtual_joint_wall;
85 
86  Vector7d tau_target; // Target effort of each joint [Nm, Nm, Nm, Nm, Nm, Nm, Nm]
87  Vector7d tau_target_last; // Last target effort of each joint [Nm, ...]
88  Vector7d q; // Measured position of each joint [rad, ...]
89  Vector7d dq; // Measured velocity of each joint [rad/s, ...]
90 
91  double f_ext_norm; // Norm of the external (cartesian) forces vector at the EE [N]
92  double contact; // Contact scaling factor (values between 0 and 1)
93  double contact_ramp_increase{0.3}; // Parameter for contact scaling factor
94  double contact_force_threshold; // Parameter for contact scaling factor [N]
95  };
96 
97  FrankaDataContainer leader_data_; // Container for data of the leader arm
98  FrankaDataContainer follower_data_; // Container for data of the follower arm
99 
100  Vector7d q_target_; // Target positions of the follower arm [rad, rad, rad, rad, rad, rad, rad]
101  Vector7d q_target_last_; // Last target positions of the follower arm [rad, ...]
102  Vector7d dq_unsaturated_; // Unsaturated target velocities of the follower arm [rad/s, ...]
103  Vector7d dq_target_; // Target velocities of the follower arm [rad/s, ...]
104  Vector7d dq_target_last_; // Last target velocities of the follower arm [rad/s, ...]
105 
106  Vector7d init_leader_q_; // Measured q of leader arm during alignment [rad]
107 
108  Vector7d dq_max_lower_; // Lower max velocities of the follower arm [rad/s, ...]
109  Vector7d dq_max_upper_; // Upper max velocities of the follower arm [rad/s, ...]
110  Vector7d ddq_max_lower_; // Lower max accelerations of the follower arm [rad/s², ...]
111  Vector7d ddq_max_upper_; // Upper max accelerations of the follower arm [rad/s², ...]
112  double velocity_ramp_shift_{0.25}; // parameter for ramping dq_max and ddq_max [rad]
113  double velocity_ramp_increase_{20}; // parameter for ramping dq_max and ddq_max
114 
115  // Max velocities of the follower arm during alignment [rad/s, ...]
116  Vector7d dq_max_align_{(Vector7d() << 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1).finished()};
117  // Max accelerations of the follower arm during alignment [rad/s², ...]
118  Vector7d ddq_max_align_{(Vector7d() << 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5).finished()};
119 
120  Vector7d alignment_error_; // Diff between follower and leader q during alignment [rad/s, ...]
121  Vector7d prev_alignment_error_; // alignment_error_ in previous control loop [rad/s, ...]
122 
123  Vector7d k_p_follower_; // p-gain for follower arm
124  Vector7d k_d_follower_; // d-gain for follower arm
125  // p-gain for follower arm during alignment
126  Vector7d k_p_follower_align_{(Vector7d() << 45.0, 45.0, 45.0, 45.0, 18.0, 11.0, 5.0).finished()};
127  // d-gain for follower arm during alignment
128  Vector7d k_d_follower_align_{(Vector7d() << 4.5, 4.5, 4.5, 4.5, 1.5, 1.5, 1.0).finished()};
129 
130  Vector7d dq_max_leader_lower_; // Soft max velocities of the leader arm [rad/s, ...]
131  Vector7d dq_max_leader_upper_; // Hard max velocities of the leader arm [rad/s, ...]
132  Vector7d k_d_leader_lower_; // d-gain for leader arm when under soft-limit
133  Vector7d k_d_leader_upper_; // d-gain for leader arm when hard limit is reached
134 
135  Vector7d k_dq_; // gain for drift compensation in follower arm
136 
137  double force_feedback_idle_{0.5}; // Applied force-feedback, when leader arm is not guided
138  double force_feedback_guiding_{0.95}; // Applied force-feeback, when leader arm is guided
139 
140  double decrease_factor_{0.95}; // Param, used when (in error state) controlling torques to zero
141 
142  TeleopStateMachine current_state_{TeleopStateMachine::ALIGN}; // Current state in teleoperation
143 
144  const double kAlignmentTolerance_{1e-2}; // Tolerance to consider a joint aligned [rad]
145 
146  void initArm(hardware_interface::RobotHW* robot_hw,
147  ros::NodeHandle& node_handle,
148  FrankaDataContainer& arm_data,
149  const std::string& arm_id,
150  const std::vector<std::string>& joint_names);
151 
152  void updateArm(FrankaDataContainer& arm_data);
153 
154  Vector7d saturateAndLimit(const Vector7d& x_calc,
155  const Vector7d& x_last,
156  const Vector7d& x_max,
157  const Vector7d& dx_max,
158  double delta_t);
159 
160  double rampParameter(double x,
161  double neg_x_asymptote,
162  double pos_x_asymptote,
163  double shift_along_x,
164  double increase_factor);
165 
166  template <typename T>
167  std::vector<T> getJointParams(const std::string& param_name, ros::NodeHandle& nh) {
168  std::vector<T> vec;
169  if (!nh.getParam(param_name, vec) || vec.size() != 7) {
170  throw std::invalid_argument("TeleopJointPDExampleController: Invalid or no parameter " +
171  nh.getNamespace() + "/" + param_name +
172  " provided, aborting controller init!");
173  }
174  return vec;
175  }
176 
177  Vector7d get7dParam(const std::string& param_name, ros::NodeHandle& nh);
178 
179  template <typename T>
180  T get1dParam(const std::string& param_name, ros::NodeHandle& nh) {
181  T out;
182  if (!nh.getParam(param_name, out)) {
183  throw std::invalid_argument("TeleopJointPDExampleController: Invalid or no parameter " +
184  nh.getNamespace() + "/" + param_name +
185  " provided, "
186  "aborting controller init!");
187  }
188  return out;
189  }
190 
191  static void getJointLimits(ros::NodeHandle& nh,
192  const std::vector<std::string>& joint_names,
193  std::array<double, 7>& upper_joint_soft_limit,
194  std::array<double, 7>& lower_joint_soft_limit);
195 
196  Vector7d leaderDamping(const Vector7d& dq);
197 
198  // Debug tool
199  bool debug_{false};
203 
205  std::unique_ptr<dynamic_reconfigure::Server<franka_example_controllers::teleop_paramConfig>>
207  void teleopParamCallback(franka_example_controllers::teleop_paramConfig& config, uint32_t level);
208 
215 
216  void publishLeaderTarget();
217  void publishFollowerTarget();
218  void publishLeaderContact();
219  void publishFollowerContact();
220  void publishMarkers();
221 };
222 } // namespace franka_example_controllers
franka_example_controllers::TeleopJointPDExampleController::velocity_ramp_shift_
double velocity_ramp_shift_
Definition: teleop_joint_pd_example_controller.h:112
franka_example_controllers::TeleopJointPDExampleController::Vector7d
Eigen::Matrix< double, 7, 1 > Vector7d
Definition: teleop_joint_pd_example_controller.h:76
franka_example_controllers::ALIGN
@ ALIGN
Definition: teleop_joint_pd_example_controller.h:34
franka_example_controllers::TeleopJointPDExampleController::publishMarkers
void publishMarkers()
Definition: teleop_joint_pd_example_controller.cpp:529
franka_example_controllers::TeleopStateMachine
TeleopStateMachine
Finite state machine that defines the states of the teleoperation phases.
Definition: teleop_joint_pd_example_controller.h:33
realtime_publisher.h
franka_example_controllers::TeleopJointPDExampleController::get7dParam
Vector7d get7dParam(const std::string &param_name, ros::NodeHandle &nh)
Definition: teleop_joint_pd_example_controller.cpp:504
franka_example_controllers::TeleopJointPDExampleController::initArm
void initArm(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &node_handle, FrankaDataContainer &arm_data, const std::string &arm_id, const std::vector< std::string > &joint_names)
Definition: teleop_joint_pd_example_controller.cpp:139
franka_example_controllers::TeleopJointPDExampleController::k_d_follower_align_
Vector7d k_d_follower_align_
Definition: teleop_joint_pd_example_controller.h:128
franka_example_controllers::TeleopJointPDExampleController::ddq_max_align_
Vector7d ddq_max_align_
Definition: teleop_joint_pd_example_controller.h:118
franka_example_controllers::TeleopJointPDExampleController::FrankaDataContainer::joint_handles
std::vector< hardware_interface::JointHandle > joint_handles
Definition: teleop_joint_pd_example_controller.h:81
franka_example_controllers::TeleopJointPDExampleController::k_d_follower_
Vector7d k_d_follower_
Definition: teleop_joint_pd_example_controller.h:124
franka_example_controllers::TeleopJointPDExampleController::saturateAndLimit
Vector7d saturateAndLimit(const Vector7d &x_calc, const Vector7d &x_last, const Vector7d &x_max, const Vector7d &dx_max, double delta_t)
Definition: teleop_joint_pd_example_controller.cpp:351
franka_example_controllers::TeleopJointPDExampleController::k_p_follower_
Vector7d k_p_follower_
Definition: teleop_joint_pd_example_controller.h:123
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
franka_example_controllers::TeleopJointPDExampleController::FrankaDataContainer::contact_force_threshold
double contact_force_threshold
Definition: teleop_joint_pd_example_controller.h:94
franka_example_controllers::TeleopJointPDExampleController::k_d_leader_upper_
Vector7d k_d_leader_upper_
Definition: teleop_joint_pd_example_controller.h:133
franka_example_controllers::TeleopJointPDExampleController::starting
void starting(const ros::Time &) override
Prepares the controller for the real-time execution.
Definition: teleop_joint_pd_example_controller.cpp:194
franka_example_controllers::TeleopJointPDExampleController::getJointLimits
static void getJointLimits(ros::NodeHandle &nh, const std::vector< std::string > &joint_names, std::array< double, 7 > &upper_joint_soft_limit, std::array< double, 7 > &lower_joint_soft_limit)
Definition: teleop_joint_pd_example_controller.cpp:425
franka_example_controllers::FrankaDataContainer
This container holds all data and parameters used to control one panda arm with a Cartesian impedance...
Definition: dual_arm_cartesian_impedance_example_controller.h:30
franka_example_controllers::TeleopJointPDExampleController::current_state_
TeleopStateMachine current_state_
Definition: teleop_joint_pd_example_controller.h:142
franka_example_controllers::TeleopJointPDExampleController::init
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &node_handle) override
Initializes the controller class to be ready to run.
Definition: teleop_joint_pd_example_controller.cpp:25
franka_example_controllers::TeleopJointPDExampleController::FrankaDataContainer::tau_target_last
Vector7d tau_target_last
Definition: teleop_joint_pd_example_controller.h:87
franka_example_controllers::TeleopJointPDExampleController::follower_data_
FrankaDataContainer follower_data_
Definition: teleop_joint_pd_example_controller.h:98
franka_example_controllers::TeleopJointPDExampleController::Vector6d
Eigen::Matrix< double, 6, 1 > Vector6d
Definition: teleop_joint_pd_example_controller.h:75
franka_example_controllers::TeleopJointPDExampleController::k_dq_
Vector7d k_dq_
Definition: teleop_joint_pd_example_controller.h:135
franka_example_controllers::TeleopJointPDExampleController::FrankaDataContainer
Definition: teleop_joint_pd_example_controller.h:79
trigger_rate.h
franka_example_controllers::TeleopJointPDExampleController::Matrix7d
Eigen::Matrix< double, 7, 7 > Matrix7d
Definition: teleop_joint_pd_example_controller.h:77
franka_example_controllers::TeleopJointPDExampleController::decrease_factor_
double decrease_factor_
Definition: teleop_joint_pd_example_controller.h:140
franka_example_controllers::TeleopJointPDExampleController::follower_contact_pub_
realtime_tools::RealtimePublisher< std_msgs::Float64 > follower_contact_pub_
Definition: teleop_joint_pd_example_controller.h:213
franka_example_controllers::TeleopJointPDExampleController
Controller class for ros_control that allows force-feedback teleoperation of a follower arm from a le...
Definition: teleop_joint_pd_example_controller.h:48
franka_example_controllers::TeleopJointPDExampleController::q_target_last_
Vector7d q_target_last_
Definition: teleop_joint_pd_example_controller.h:101
franka_example_controllers::TeleopJointPDExampleController::publishFollowerContact
void publishFollowerContact()
Definition: teleop_joint_pd_example_controller.cpp:497
franka_example_controllers::TeleopJointPDExampleController::leader_damping_scaling_
double leader_damping_scaling_
Definition: teleop_joint_pd_example_controller.h:201
franka_example_controllers::TRACK
@ TRACK
Definition: teleop_joint_pd_example_controller.h:35
franka_example_controllers::TeleopJointPDExampleController::publishLeaderContact
void publishLeaderContact()
Definition: teleop_joint_pd_example_controller.cpp:490
franka_example_controllers::TeleopJointPDExampleController::dq_max_upper_
Vector7d dq_max_upper_
Definition: teleop_joint_pd_example_controller.h:109
realtime_tools::RealtimePublisher< sensor_msgs::JointState >
franka_example_controllers
Definition: cartesian_impedance_example_controller.h:23
franka_example_controllers::TeleopJointPDExampleController::dq_unsaturated_
Vector7d dq_unsaturated_
Definition: teleop_joint_pd_example_controller.h:102
franka_example_controllers::TeleopJointPDExampleController::FrankaDataContainer::state_handle
std::unique_ptr< franka_hw::FrankaStateHandle > state_handle
Definition: teleop_joint_pd_example_controller.h:80
joint_command_interface.h
franka_example_controllers::TeleopJointPDExampleController::ddq_max_upper_
Vector7d ddq_max_upper_
Definition: teleop_joint_pd_example_controller.h:111
franka_example_controllers::TeleopJointPDExampleController::FrankaDataContainer::virtual_joint_wall
std::unique_ptr< JointWallContainer< 7 > > virtual_joint_wall
Definition: teleop_joint_pd_example_controller.h:84
hardware_interface::RobotHW
franka_example_controllers::TeleopJointPDExampleController::teleopParamCallback
void teleopParamCallback(franka_example_controllers::teleop_paramConfig &config, uint32_t level)
Definition: teleop_joint_pd_example_controller.cpp:377
franka_example_controllers::TeleopJointPDExampleController::dq_max_leader_lower_
Vector7d dq_max_leader_lower_
Definition: teleop_joint_pd_example_controller.h:130
controller_interface::MultiInterfaceController
franka_example_controllers::TeleopJointPDExampleController::dq_target_
Vector7d dq_target_
Definition: teleop_joint_pd_example_controller.h:103
franka_example_controllers::TeleopJointPDExampleController::dq_max_align_
Vector7d dq_max_align_
Definition: teleop_joint_pd_example_controller.h:116
franka_example_controllers::TeleopJointPDExampleController::marker_pub_
realtime_tools::RealtimePublisher< visualization_msgs::MarkerArray > marker_pub_
Definition: teleop_joint_pd_example_controller.h:214
franka_example_controllers::TeleopJointPDExampleController::dynamic_server_teleop_param_
std::unique_ptr< dynamic_reconfigure::Server< franka_example_controllers::teleop_paramConfig > > dynamic_server_teleop_param_
Definition: teleop_joint_pd_example_controller.h:206
franka_example_controllers::TeleopJointPDExampleController::leader_data_
FrankaDataContainer leader_data_
Definition: teleop_joint_pd_example_controller.h:97
franka_example_controllers::TeleopJointPDExampleController::debug_
bool debug_
Definition: teleop_joint_pd_example_controller.h:199
franka_example_controllers::TeleopJointPDExampleController::get1dParam
T get1dParam(const std::string &param_name, ros::NodeHandle &nh)
Definition: teleop_joint_pd_example_controller.h:180
dual_arm_interactive_marker.x
x
Definition: dual_arm_interactive_marker.py:159
franka_example_controllers::TeleopJointPDExampleController::updateArm
void updateArm(FrankaDataContainer &arm_data)
Definition: teleop_joint_pd_example_controller.cpp:345
franka_example_controllers::TeleopJointPDExampleController::publishLeaderTarget
void publishLeaderTarget()
Definition: teleop_joint_pd_example_controller.cpp:466
franka_example_controllers::TeleopJointPDExampleController::publish_rate_
franka_hw::TriggerRate publish_rate_
Definition: teleop_joint_pd_example_controller.h:209
franka_example_controllers::TeleopJointPDExampleController::q_target_
Vector7d q_target_
Definition: teleop_joint_pd_example_controller.h:100
franka_state_interface.h
franka_example_controllers::TeleopJointPDExampleController::FrankaDataContainer::tau_target
Vector7d tau_target
Definition: teleop_joint_pd_example_controller.h:86
franka_example_controllers::TeleopJointPDExampleController::alignment_error_
Vector7d alignment_error_
Definition: teleop_joint_pd_example_controller.h:120
franka_example_controllers::TeleopJointPDExampleController::leader_target_pub_
realtime_tools::RealtimePublisher< sensor_msgs::JointState > leader_target_pub_
Definition: teleop_joint_pd_example_controller.h:210
franka_example_controllers::TeleopJointPDExampleController::dq_max_leader_upper_
Vector7d dq_max_leader_upper_
Definition: teleop_joint_pd_example_controller.h:131
franka_example_controllers::TeleopJointPDExampleController::dq_max_lower_
Vector7d dq_max_lower_
Definition: teleop_joint_pd_example_controller.h:108
franka_example_controllers::TeleopJointPDExampleController::FrankaDataContainer::contact
double contact
Definition: teleop_joint_pd_example_controller.h:92
ros::Time
franka_example_controllers::TeleopJointPDExampleController::force_feedback_idle_
double force_feedback_idle_
Definition: teleop_joint_pd_example_controller.h:137
franka_example_controllers::TeleopJointPDExampleController::follower_stiffness_scaling_
double follower_stiffness_scaling_
Definition: teleop_joint_pd_example_controller.h:202
franka_example_controllers::TeleopJointPDExampleController::ddq_max_lower_
Vector7d ddq_max_lower_
Definition: teleop_joint_pd_example_controller.h:110
franka_example_controllers::TeleopJointPDExampleController::leaderDamping
Vector7d leaderDamping(const Vector7d &dq)
Definition: teleop_joint_pd_example_controller.cpp:510
franka_example_controllers::TeleopJointPDExampleController::kAlignmentTolerance_
const double kAlignmentTolerance_
Definition: teleop_joint_pd_example_controller.h:144
Vector7d
Eigen::Matrix< double, 7, 1 > Vector7d
Definition: teleop_joint_pd_example_controller.cpp:19
franka_example_controllers::TeleopJointPDExampleController::dynamic_reconfigure_mutex_
std::mutex dynamic_reconfigure_mutex_
Definition: teleop_joint_pd_example_controller.h:200
franka_example_controllers::TeleopJointPDExampleController::k_d_leader_lower_
Vector7d k_d_leader_lower_
Definition: teleop_joint_pd_example_controller.h:132
franka_example_controllers::TeleopJointPDExampleController::rampParameter
double rampParameter(double x, double neg_x_asymptote, double pos_x_asymptote, double shift_along_x, double increase_factor)
Definition: teleop_joint_pd_example_controller.cpp:366
franka_example_controllers::TeleopJointPDExampleController::follower_target_pub_
realtime_tools::RealtimePublisher< sensor_msgs::JointState > follower_target_pub_
Definition: teleop_joint_pd_example_controller.h:211
franka_example_controllers::TeleopJointPDExampleController::FrankaDataContainer::q
Vector7d q
Definition: teleop_joint_pd_example_controller.h:88
franka_example_controllers::TeleopJointPDExampleController::dq_target_last_
Vector7d dq_target_last_
Definition: teleop_joint_pd_example_controller.h:104
robot_hw.h
franka_example_controllers::TeleopJointPDExampleController::FrankaDataContainer::contact_ramp_increase
double contact_ramp_increase
Definition: teleop_joint_pd_example_controller.h:93
franka_hw::TriggerRate
franka_example_controllers::TeleopJointPDExampleController::getJointParams
std::vector< T > getJointParams(const std::string &param_name, ros::NodeHandle &nh)
Definition: teleop_joint_pd_example_controller.h:167
franka_example_controllers::TeleopJointPDExampleController::FrankaDataContainer::f_ext_norm
double f_ext_norm
Definition: teleop_joint_pd_example_controller.h:91
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
franka_example_controllers::TeleopJointPDExampleController::force_feedback_guiding_
double force_feedback_guiding_
Definition: teleop_joint_pd_example_controller.h:138
franka_example_controllers::TeleopJointPDExampleController::velocity_ramp_increase_
double velocity_ramp_increase_
Definition: teleop_joint_pd_example_controller.h:113
joint_wall.h
franka_example_controllers::TeleopJointPDExampleController::leader_contact_pub_
realtime_tools::RealtimePublisher< std_msgs::Float64 > leader_contact_pub_
Definition: teleop_joint_pd_example_controller.h:212
ros::Duration
franka_example_controllers::TeleopJointPDExampleController::init_leader_q_
Vector7d init_leader_q_
Definition: teleop_joint_pd_example_controller.h:106
franka_example_controllers::TeleopJointPDExampleController::dynamic_reconfigure_teleop_param_node_
ros::NodeHandle dynamic_reconfigure_teleop_param_node_
Definition: teleop_joint_pd_example_controller.h:204
ros::NodeHandle
franka_example_controllers::TeleopJointPDExampleController::prev_alignment_error_
Vector7d prev_alignment_error_
Definition: teleop_joint_pd_example_controller.h:121
franka_example_controllers::TeleopJointPDExampleController::publishFollowerTarget
void publishFollowerTarget()
Definition: teleop_joint_pd_example_controller.cpp:478
franka_example_controllers::TeleopJointPDExampleController::update
void update(const ros::Time &, const ros::Duration &period) override
Computes the control-law and commands the resulting joint torques to the robots.
Definition: teleop_joint_pd_example_controller.cpp:215
franka_example_controllers::TeleopJointPDExampleController::FrankaDataContainer::dq
Vector7d dq
Definition: teleop_joint_pd_example_controller.h:89
multi_interface_controller.h
franka_example_controllers::TeleopJointPDExampleController::k_p_follower_align_
Vector7d k_p_follower_align_
Definition: teleop_joint_pd_example_controller.h:126


franka_example_controllers
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 02:33:26