Go to the documentation of this file.
6 #include <franka_example_controllers/teleop_paramConfig.h>
10 #include <control_msgs/GripperCommandAction.h>
12 #include <dynamic_reconfigure/server.h>
17 #include <sensor_msgs/JointState.h>
18 #include <std_msgs/Float64.h>
19 #include <visualization_msgs/MarkerArray.h>
21 #include <Eigen/Dense>
49 hardware_interface::EffortJointInterface,
50 franka_hw::FrankaStateInterface> {
149 const std::string& arm_id,
150 const std::vector<std::string>& joint_names);
161 double neg_x_asymptote,
162 double pos_x_asymptote,
163 double shift_along_x,
164 double increase_factor);
166 template <
typename T>
169 if (!nh.
getParam(param_name, vec) || vec.size() != 7) {
170 throw std::invalid_argument(
"TeleopJointPDExampleController: Invalid or no parameter " +
172 " provided, aborting controller init!");
179 template <
typename T>
182 if (!nh.
getParam(param_name, out)) {
183 throw std::invalid_argument(
"TeleopJointPDExampleController: Invalid or no parameter " +
186 "aborting controller init!");
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);
205 std::unique_ptr<dynamic_reconfigure::Server<franka_example_controllers::teleop_paramConfig>>
207 void teleopParamCallback(franka_example_controllers::teleop_paramConfig& config, uint32_t level);
double velocity_ramp_shift_
Eigen::Matrix< double, 7, 1 > Vector7d
TeleopStateMachine
Finite state machine that defines the states of the teleoperation phases.
Vector7d get7dParam(const std::string ¶m_name, ros::NodeHandle &nh)
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)
Vector7d k_d_follower_align_
std::vector< hardware_interface::JointHandle > joint_handles
Vector7d saturateAndLimit(const Vector7d &x_calc, const Vector7d &x_last, const Vector7d &x_max, const Vector7d &dx_max, double delta_t)
bool getParam(const std::string &key, bool &b) const
double contact_force_threshold
Vector7d k_d_leader_upper_
void starting(const ros::Time &) override
Prepares the controller for the real-time execution.
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)
This container holds all data and parameters used to control one panda arm with a Cartesian impedance...
TeleopStateMachine current_state_
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &node_handle) override
Initializes the controller class to be ready to run.
FrankaDataContainer follower_data_
Eigen::Matrix< double, 6, 1 > Vector6d
Eigen::Matrix< double, 7, 7 > Matrix7d
realtime_tools::RealtimePublisher< std_msgs::Float64 > follower_contact_pub_
Controller class for ros_control that allows force-feedback teleoperation of a follower arm from a le...
void publishFollowerContact()
double leader_damping_scaling_
void publishLeaderContact()
std::unique_ptr< franka_hw::FrankaStateHandle > state_handle
std::unique_ptr< JointWallContainer< 7 > > virtual_joint_wall
void teleopParamCallback(franka_example_controllers::teleop_paramConfig &config, uint32_t level)
Vector7d dq_max_leader_lower_
realtime_tools::RealtimePublisher< visualization_msgs::MarkerArray > marker_pub_
std::unique_ptr< dynamic_reconfigure::Server< franka_example_controllers::teleop_paramConfig > > dynamic_server_teleop_param_
FrankaDataContainer leader_data_
T get1dParam(const std::string ¶m_name, ros::NodeHandle &nh)
void updateArm(FrankaDataContainer &arm_data)
void publishLeaderTarget()
franka_hw::TriggerRate publish_rate_
Vector7d alignment_error_
realtime_tools::RealtimePublisher< sensor_msgs::JointState > leader_target_pub_
Vector7d dq_max_leader_upper_
double force_feedback_idle_
double follower_stiffness_scaling_
Vector7d leaderDamping(const Vector7d &dq)
const double kAlignmentTolerance_
Eigen::Matrix< double, 7, 1 > Vector7d
std::mutex dynamic_reconfigure_mutex_
Vector7d k_d_leader_lower_
double rampParameter(double x, double neg_x_asymptote, double pos_x_asymptote, double shift_along_x, double increase_factor)
realtime_tools::RealtimePublisher< sensor_msgs::JointState > follower_target_pub_
double contact_ramp_increase
std::vector< T > getJointParams(const std::string ¶m_name, ros::NodeHandle &nh)
const std::string & getNamespace() const
double force_feedback_guiding_
double velocity_ramp_increase_
realtime_tools::RealtimePublisher< std_msgs::Float64 > leader_contact_pub_
ros::NodeHandle dynamic_reconfigure_teleop_param_node_
Vector7d prev_alignment_error_
void publishFollowerTarget()
void update(const ros::Time &, const ros::Duration &period) override
Computes the control-law and commands the resulting joint torques to the robots.
Vector7d k_p_follower_align_