Classes | Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
franka_example_controllers::TeleopJointPDExampleController Class Reference

Controller class for ros_control that allows force-feedback teleoperation of a follower arm from a leader arm. More...

#include <teleop_joint_pd_example_controller.h>

Inheritance diagram for franka_example_controllers::TeleopJointPDExampleController:
Inheritance graph
[legend]

Classes

struct  FrankaDataContainer
 

Public Member Functions

bool init (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &node_handle) override
 Initializes the controller class to be ready to run. More...
 
void starting (const ros::Time &) override
 Prepares the controller for the real-time execution. More...
 
void update (const ros::Time &, const ros::Duration &period) override
 Computes the control-law and commands the resulting joint torques to the robots. More...
 
- Public Member Functions inherited from controller_interface::MultiInterfaceController< hardware_interface::EffortJointInterface, franka_hw::FrankaStateInterface >
virtual bool init (hardware_interface::RobotHW *, ros::NodeHandle &, ros::NodeHandle &)
 
 MultiInterfaceController (bool allow_optional_interfaces=false)
 
- Public Member Functions inherited from controller_interface::ControllerBase
virtual void aborting (const ros::Time &)
 
virtual void aborting (const ros::Time &)
 
bool abortRequest (const ros::Time &time)
 
bool abortRequest (const ros::Time &time)
 
 ControllerBase ()=default
 
 ControllerBase (const ControllerBase &)=delete
 
 ControllerBase (ControllerBase &&)=delete
 
bool isAborted () const
 
bool isAborted () const
 
bool isInitialized () const
 
bool isInitialized () const
 
bool isRunning () const
 
bool isRunning () const
 
bool isStopped () const
 
bool isStopped () const
 
bool isWaiting () const
 
bool isWaiting () const
 
ControllerBaseoperator= (const ControllerBase &)=delete
 
ControllerBaseoperator= (ControllerBase &&)=delete
 
bool startRequest (const ros::Time &time)
 
bool startRequest (const ros::Time &time)
 
virtual void stopping (const ros::Time &)
 
virtual void stopping (const ros::Time &)
 
bool stopRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
virtual void waiting (const ros::Time &)
 
virtual void waiting (const ros::Time &)
 
bool waitRequest (const ros::Time &time)
 
bool waitRequest (const ros::Time &time)
 
virtual ~ControllerBase ()=default
 

Private Types

using Matrix7d = Eigen::Matrix< double, 7, 7 >
 
using Vector6d = Eigen::Matrix< double, 6, 1 >
 
using Vector7d = Eigen::Matrix< double, 7, 1 >
 

Private Member Functions

template<typename T >
get1dParam (const std::string &param_name, ros::NodeHandle &nh)
 
Vector7d get7dParam (const std::string &param_name, ros::NodeHandle &nh)
 
template<typename T >
std::vector< T > getJointParams (const std::string &param_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 leaderDamping (const Vector7d &dq)
 
void publishFollowerContact ()
 
void publishFollowerTarget ()
 
void publishLeaderContact ()
 
void publishLeaderTarget ()
 
void publishMarkers ()
 
double rampParameter (double x, double neg_x_asymptote, double pos_x_asymptote, double shift_along_x, double increase_factor)
 
Vector7d saturateAndLimit (const Vector7d &x_calc, const Vector7d &x_last, const Vector7d &x_max, const Vector7d &dx_max, double delta_t)
 
void teleopParamCallback (franka_example_controllers::teleop_paramConfig &config, uint32_t level)
 
void updateArm (FrankaDataContainer &arm_data)
 

Static Private Member Functions

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)
 

Private Attributes

Vector7d alignment_error_
 
TeleopStateMachine current_state_ {TeleopStateMachine::ALIGN}
 
Vector7d ddq_max_align_ {(Vector7d() << 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5).finished()}
 
Vector7d ddq_max_lower_
 
Vector7d ddq_max_upper_
 
bool debug_ {false}
 
double decrease_factor_ {0.95}
 
Vector7d dq_max_align_ {(Vector7d() << 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1).finished()}
 
Vector7d dq_max_leader_lower_
 
Vector7d dq_max_leader_upper_
 
Vector7d dq_max_lower_
 
Vector7d dq_max_upper_
 
Vector7d dq_target_
 
Vector7d dq_target_last_
 
Vector7d dq_unsaturated_
 
std::mutex dynamic_reconfigure_mutex_
 
ros::NodeHandle dynamic_reconfigure_teleop_param_node_
 
std::unique_ptr< dynamic_reconfigure::Server< franka_example_controllers::teleop_paramConfig > > dynamic_server_teleop_param_
 
realtime_tools::RealtimePublisher< std_msgs::Float64 > follower_contact_pub_
 
FrankaDataContainer follower_data_
 
double follower_stiffness_scaling_ {1.0}
 
realtime_tools::RealtimePublisher< sensor_msgs::JointState > follower_target_pub_
 
double force_feedback_guiding_ {0.95}
 
double force_feedback_idle_ {0.5}
 
Vector7d init_leader_q_
 
Vector7d k_d_follower_
 
Vector7d k_d_follower_align_ {(Vector7d() << 4.5, 4.5, 4.5, 4.5, 1.5, 1.5, 1.0).finished()}
 
Vector7d k_d_leader_lower_
 
Vector7d k_d_leader_upper_
 
Vector7d k_dq_
 
Vector7d k_p_follower_
 
Vector7d k_p_follower_align_ {(Vector7d() << 45.0, 45.0, 45.0, 45.0, 18.0, 11.0, 5.0).finished()}
 
const double kAlignmentTolerance_ {1e-2}
 
realtime_tools::RealtimePublisher< std_msgs::Float64 > leader_contact_pub_
 
double leader_damping_scaling_ {1.0}
 
FrankaDataContainer leader_data_
 
realtime_tools::RealtimePublisher< sensor_msgs::JointState > leader_target_pub_
 
realtime_tools::RealtimePublisher< visualization_msgs::MarkerArray > marker_pub_
 
Vector7d prev_alignment_error_
 
franka_hw::TriggerRate publish_rate_ {60.0}
 
Vector7d q_target_
 
Vector7d q_target_last_
 
double velocity_ramp_increase_ {20}
 
double velocity_ramp_shift_ {0.25}
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
- Public Attributes inherited from controller_interface::ControllerBase
 ABORTED
 
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  state_
 
 STOPPED
 
 WAITING
 
- Protected Member Functions inherited from controller_interface::MultiInterfaceController< hardware_interface::EffortJointInterface, franka_hw::FrankaStateInterface >
bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override
 
- Static Protected Member Functions inherited from controller_interface::MultiInterfaceController< hardware_interface::EffortJointInterface, franka_hw::FrankaStateInterface >
static void clearClaims (hardware_interface::RobotHW *robot_hw)
 
static void extractInterfaceResources (hardware_interface::RobotHW *robot_hw_in, hardware_interface::RobotHW *robot_hw_out)
 
static bool hasRequiredInterfaces (hardware_interface::RobotHW *robot_hw)
 
static void populateClaimedResources (hardware_interface::RobotHW *robot_hw, ClaimedResources &claimed_resources)
 
- Protected Attributes inherited from controller_interface::MultiInterfaceController< hardware_interface::EffortJointInterface, franka_hw::FrankaStateInterface >
bool allow_optional_interfaces_
 
hardware_interface::RobotHW robot_hw_ctrl_
 

Detailed Description

Controller class for ros_control that allows force-feedback teleoperation of a follower arm from a leader arm.

Smooth tracking is implemented by integrating a velocity signal, which is calculated by limiting and saturating the velocity of the leader arm and a drift compensation. The torque control of the follower arm is implemented by a simple PD-controller. The leader arm is slightly damped to reduce vibrations. Force-feedback is applied to the leader arm when the external forces on the follower arm exceed a configured threshold. While the leader arm is unguided (not in contact), the applied force-feedback will be reduced.

Definition at line 48 of file teleop_joint_pd_example_controller.h.

Member Typedef Documentation

◆ Matrix7d

using franka_example_controllers::TeleopJointPDExampleController::Matrix7d = Eigen::Matrix<double, 7, 7>
private

Definition at line 77 of file teleop_joint_pd_example_controller.h.

◆ Vector6d

using franka_example_controllers::TeleopJointPDExampleController::Vector6d = Eigen::Matrix<double, 6, 1>
private

Definition at line 75 of file teleop_joint_pd_example_controller.h.

◆ Vector7d

using franka_example_controllers::TeleopJointPDExampleController::Vector7d = Eigen::Matrix<double, 7, 1>
private

Definition at line 76 of file teleop_joint_pd_example_controller.h.

Member Function Documentation

◆ get1dParam()

template<typename T >
T franka_example_controllers::TeleopJointPDExampleController::get1dParam ( const std::string &  param_name,
ros::NodeHandle nh 
)
inlineprivate

Definition at line 180 of file teleop_joint_pd_example_controller.h.

◆ get7dParam()

Vector7d franka_example_controllers::TeleopJointPDExampleController::get7dParam ( const std::string &  param_name,
ros::NodeHandle nh 
)
private

Definition at line 504 of file teleop_joint_pd_example_controller.cpp.

◆ getJointLimits()

void franka_example_controllers::TeleopJointPDExampleController::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 
)
staticprivate

Definition at line 425 of file teleop_joint_pd_example_controller.cpp.

◆ getJointParams()

template<typename T >
std::vector<T> franka_example_controllers::TeleopJointPDExampleController::getJointParams ( const std::string &  param_name,
ros::NodeHandle nh 
)
inlineprivate

Definition at line 167 of file teleop_joint_pd_example_controller.h.

◆ init()

bool franka_example_controllers::TeleopJointPDExampleController::init ( hardware_interface::RobotHW robot_hw,
ros::NodeHandle node_handle 
)
overridevirtual

Initializes the controller class to be ready to run.

Parameters
[in]robot_hwPointer to a RobotHW class to get interfaces and resource handles.
[in]node_handleNodehandle that allows getting parameterizations from the server and starting publisher

Reimplemented from controller_interface::MultiInterfaceController< hardware_interface::EffortJointInterface, franka_hw::FrankaStateInterface >.

Definition at line 25 of file teleop_joint_pd_example_controller.cpp.

◆ initArm()

void franka_example_controllers::TeleopJointPDExampleController::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 
)
private

Definition at line 139 of file teleop_joint_pd_example_controller.cpp.

◆ leaderDamping()

Vector7d franka_example_controllers::TeleopJointPDExampleController::leaderDamping ( const Vector7d dq)
private

Definition at line 510 of file teleop_joint_pd_example_controller.cpp.

◆ publishFollowerContact()

void franka_example_controllers::TeleopJointPDExampleController::publishFollowerContact ( )
private

Definition at line 497 of file teleop_joint_pd_example_controller.cpp.

◆ publishFollowerTarget()

void franka_example_controllers::TeleopJointPDExampleController::publishFollowerTarget ( )
private

Definition at line 478 of file teleop_joint_pd_example_controller.cpp.

◆ publishLeaderContact()

void franka_example_controllers::TeleopJointPDExampleController::publishLeaderContact ( )
private

Definition at line 490 of file teleop_joint_pd_example_controller.cpp.

◆ publishLeaderTarget()

void franka_example_controllers::TeleopJointPDExampleController::publishLeaderTarget ( )
private

Definition at line 466 of file teleop_joint_pd_example_controller.cpp.

◆ publishMarkers()

void franka_example_controllers::TeleopJointPDExampleController::publishMarkers ( )
private

Definition at line 529 of file teleop_joint_pd_example_controller.cpp.

◆ rampParameter()

double franka_example_controllers::TeleopJointPDExampleController::rampParameter ( double  x,
double  neg_x_asymptote,
double  pos_x_asymptote,
double  shift_along_x,
double  increase_factor 
)
private

Definition at line 366 of file teleop_joint_pd_example_controller.cpp.

◆ saturateAndLimit()

Eigen::Matrix< double, 7, 1 > franka_example_controllers::TeleopJointPDExampleController::saturateAndLimit ( const Vector7d x_calc,
const Vector7d x_last,
const Vector7d x_max,
const Vector7d dx_max,
double  delta_t 
)
private

Definition at line 351 of file teleop_joint_pd_example_controller.cpp.

◆ starting()

void franka_example_controllers::TeleopJointPDExampleController::starting ( const ros::Time )
overridevirtual

Prepares the controller for the real-time execution.

This method is executed once every time the controller is started and runs in real-time

Reimplemented from controller_interface::ControllerBase.

Definition at line 194 of file teleop_joint_pd_example_controller.cpp.

◆ teleopParamCallback()

void franka_example_controllers::TeleopJointPDExampleController::teleopParamCallback ( franka_example_controllers::teleop_paramConfig &  config,
uint32_t  level 
)
private

Definition at line 377 of file teleop_joint_pd_example_controller.cpp.

◆ update()

void franka_example_controllers::TeleopJointPDExampleController::update ( const ros::Time ,
const ros::Duration period 
)
overridevirtual

Computes the control-law and commands the resulting joint torques to the robots.

Parameters
[in]periodThe control period (here 0.001s)

Implements controller_interface::ControllerBase.

Definition at line 215 of file teleop_joint_pd_example_controller.cpp.

◆ updateArm()

void franka_example_controllers::TeleopJointPDExampleController::updateArm ( FrankaDataContainer arm_data)
private

Definition at line 345 of file teleop_joint_pd_example_controller.cpp.

Member Data Documentation

◆ alignment_error_

Vector7d franka_example_controllers::TeleopJointPDExampleController::alignment_error_
private

Definition at line 120 of file teleop_joint_pd_example_controller.h.

◆ current_state_

TeleopStateMachine franka_example_controllers::TeleopJointPDExampleController::current_state_ {TeleopStateMachine::ALIGN}
private

Definition at line 142 of file teleop_joint_pd_example_controller.h.

◆ ddq_max_align_

Vector7d franka_example_controllers::TeleopJointPDExampleController::ddq_max_align_ {(Vector7d() << 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5).finished()}
private

Definition at line 118 of file teleop_joint_pd_example_controller.h.

◆ ddq_max_lower_

Vector7d franka_example_controllers::TeleopJointPDExampleController::ddq_max_lower_
private

Definition at line 110 of file teleop_joint_pd_example_controller.h.

◆ ddq_max_upper_

Vector7d franka_example_controllers::TeleopJointPDExampleController::ddq_max_upper_
private

Definition at line 111 of file teleop_joint_pd_example_controller.h.

◆ debug_

bool franka_example_controllers::TeleopJointPDExampleController::debug_ {false}
private

Definition at line 199 of file teleop_joint_pd_example_controller.h.

◆ decrease_factor_

double franka_example_controllers::TeleopJointPDExampleController::decrease_factor_ {0.95}
private

Definition at line 140 of file teleop_joint_pd_example_controller.h.

◆ dq_max_align_

Vector7d franka_example_controllers::TeleopJointPDExampleController::dq_max_align_ {(Vector7d() << 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1).finished()}
private

Definition at line 116 of file teleop_joint_pd_example_controller.h.

◆ dq_max_leader_lower_

Vector7d franka_example_controllers::TeleopJointPDExampleController::dq_max_leader_lower_
private

Definition at line 130 of file teleop_joint_pd_example_controller.h.

◆ dq_max_leader_upper_

Vector7d franka_example_controllers::TeleopJointPDExampleController::dq_max_leader_upper_
private

Definition at line 131 of file teleop_joint_pd_example_controller.h.

◆ dq_max_lower_

Vector7d franka_example_controllers::TeleopJointPDExampleController::dq_max_lower_
private

Definition at line 108 of file teleop_joint_pd_example_controller.h.

◆ dq_max_upper_

Vector7d franka_example_controllers::TeleopJointPDExampleController::dq_max_upper_
private

Definition at line 109 of file teleop_joint_pd_example_controller.h.

◆ dq_target_

Vector7d franka_example_controllers::TeleopJointPDExampleController::dq_target_
private

Definition at line 103 of file teleop_joint_pd_example_controller.h.

◆ dq_target_last_

Vector7d franka_example_controllers::TeleopJointPDExampleController::dq_target_last_
private

Definition at line 104 of file teleop_joint_pd_example_controller.h.

◆ dq_unsaturated_

Vector7d franka_example_controllers::TeleopJointPDExampleController::dq_unsaturated_
private

Definition at line 102 of file teleop_joint_pd_example_controller.h.

◆ dynamic_reconfigure_mutex_

std::mutex franka_example_controllers::TeleopJointPDExampleController::dynamic_reconfigure_mutex_
private

Definition at line 200 of file teleop_joint_pd_example_controller.h.

◆ dynamic_reconfigure_teleop_param_node_

ros::NodeHandle franka_example_controllers::TeleopJointPDExampleController::dynamic_reconfigure_teleop_param_node_
private

Definition at line 204 of file teleop_joint_pd_example_controller.h.

◆ dynamic_server_teleop_param_

std::unique_ptr<dynamic_reconfigure::Server<franka_example_controllers::teleop_paramConfig> > franka_example_controllers::TeleopJointPDExampleController::dynamic_server_teleop_param_
private

Definition at line 206 of file teleop_joint_pd_example_controller.h.

◆ follower_contact_pub_

realtime_tools::RealtimePublisher<std_msgs::Float64> franka_example_controllers::TeleopJointPDExampleController::follower_contact_pub_
private

Definition at line 213 of file teleop_joint_pd_example_controller.h.

◆ follower_data_

FrankaDataContainer franka_example_controllers::TeleopJointPDExampleController::follower_data_
private

Definition at line 98 of file teleop_joint_pd_example_controller.h.

◆ follower_stiffness_scaling_

double franka_example_controllers::TeleopJointPDExampleController::follower_stiffness_scaling_ {1.0}
private

Definition at line 202 of file teleop_joint_pd_example_controller.h.

◆ follower_target_pub_

realtime_tools::RealtimePublisher<sensor_msgs::JointState> franka_example_controllers::TeleopJointPDExampleController::follower_target_pub_
private

Definition at line 211 of file teleop_joint_pd_example_controller.h.

◆ force_feedback_guiding_

double franka_example_controllers::TeleopJointPDExampleController::force_feedback_guiding_ {0.95}
private

Definition at line 138 of file teleop_joint_pd_example_controller.h.

◆ force_feedback_idle_

double franka_example_controllers::TeleopJointPDExampleController::force_feedback_idle_ {0.5}
private

Definition at line 137 of file teleop_joint_pd_example_controller.h.

◆ init_leader_q_

Vector7d franka_example_controllers::TeleopJointPDExampleController::init_leader_q_
private

Definition at line 106 of file teleop_joint_pd_example_controller.h.

◆ k_d_follower_

Vector7d franka_example_controllers::TeleopJointPDExampleController::k_d_follower_
private

Definition at line 124 of file teleop_joint_pd_example_controller.h.

◆ k_d_follower_align_

Vector7d franka_example_controllers::TeleopJointPDExampleController::k_d_follower_align_ {(Vector7d() << 4.5, 4.5, 4.5, 4.5, 1.5, 1.5, 1.0).finished()}
private

Definition at line 128 of file teleop_joint_pd_example_controller.h.

◆ k_d_leader_lower_

Vector7d franka_example_controllers::TeleopJointPDExampleController::k_d_leader_lower_
private

Definition at line 132 of file teleop_joint_pd_example_controller.h.

◆ k_d_leader_upper_

Vector7d franka_example_controllers::TeleopJointPDExampleController::k_d_leader_upper_
private

Definition at line 133 of file teleop_joint_pd_example_controller.h.

◆ k_dq_

Vector7d franka_example_controllers::TeleopJointPDExampleController::k_dq_
private

Definition at line 135 of file teleop_joint_pd_example_controller.h.

◆ k_p_follower_

Vector7d franka_example_controllers::TeleopJointPDExampleController::k_p_follower_
private

Definition at line 123 of file teleop_joint_pd_example_controller.h.

◆ k_p_follower_align_

Vector7d franka_example_controllers::TeleopJointPDExampleController::k_p_follower_align_ {(Vector7d() << 45.0, 45.0, 45.0, 45.0, 18.0, 11.0, 5.0).finished()}
private

Definition at line 126 of file teleop_joint_pd_example_controller.h.

◆ kAlignmentTolerance_

const double franka_example_controllers::TeleopJointPDExampleController::kAlignmentTolerance_ {1e-2}
private

Definition at line 144 of file teleop_joint_pd_example_controller.h.

◆ leader_contact_pub_

realtime_tools::RealtimePublisher<std_msgs::Float64> franka_example_controllers::TeleopJointPDExampleController::leader_contact_pub_
private

Definition at line 212 of file teleop_joint_pd_example_controller.h.

◆ leader_damping_scaling_

double franka_example_controllers::TeleopJointPDExampleController::leader_damping_scaling_ {1.0}
private

Definition at line 201 of file teleop_joint_pd_example_controller.h.

◆ leader_data_

FrankaDataContainer franka_example_controllers::TeleopJointPDExampleController::leader_data_
private

Definition at line 97 of file teleop_joint_pd_example_controller.h.

◆ leader_target_pub_

realtime_tools::RealtimePublisher<sensor_msgs::JointState> franka_example_controllers::TeleopJointPDExampleController::leader_target_pub_
private

Definition at line 210 of file teleop_joint_pd_example_controller.h.

◆ marker_pub_

realtime_tools::RealtimePublisher<visualization_msgs::MarkerArray> franka_example_controllers::TeleopJointPDExampleController::marker_pub_
private

Definition at line 214 of file teleop_joint_pd_example_controller.h.

◆ prev_alignment_error_

Vector7d franka_example_controllers::TeleopJointPDExampleController::prev_alignment_error_
private

Definition at line 121 of file teleop_joint_pd_example_controller.h.

◆ publish_rate_

franka_hw::TriggerRate franka_example_controllers::TeleopJointPDExampleController::publish_rate_ {60.0}
private

Definition at line 209 of file teleop_joint_pd_example_controller.h.

◆ q_target_

Vector7d franka_example_controllers::TeleopJointPDExampleController::q_target_
private

Definition at line 100 of file teleop_joint_pd_example_controller.h.

◆ q_target_last_

Vector7d franka_example_controllers::TeleopJointPDExampleController::q_target_last_
private

Definition at line 101 of file teleop_joint_pd_example_controller.h.

◆ velocity_ramp_increase_

double franka_example_controllers::TeleopJointPDExampleController::velocity_ramp_increase_ {20}
private

Definition at line 113 of file teleop_joint_pd_example_controller.h.

◆ velocity_ramp_shift_

double franka_example_controllers::TeleopJointPDExampleController::velocity_ramp_shift_ {0.25}
private

Definition at line 112 of file teleop_joint_pd_example_controller.h.


The documentation for this class was generated from the following files:


franka_example_controllers
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 03:06:01