Public Member Functions | Private Member Functions | Private Attributes | List of all members
franka_example_controllers::CartesianImpedanceExampleController Class Reference

#include <cartesian_impedance_example_controller.h>

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

Public Member Functions

bool init (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &node_handle) override
 
void starting (const ros::Time &) override
 
void update (const ros::Time &, const ros::Duration &period) override
 
- Public Member Functions inherited from controller_interface::MultiInterfaceController< franka_hw::FrankaModelInterface, hardware_interface::EffortJointInterface, franka_hw::FrankaStateInterface >
virtual bool init (hardware_interface::RobotHW *, ros::NodeHandle &, ros::NodeHandle &)
 
 MultiInterfaceController (bool allow_optional_interfaces=false)
 
virtual ~MultiInterfaceController ()
 
- Public Member Functions inherited from controller_interface::ControllerBase
 ControllerBase ()
 
bool isRunning ()
 
bool isRunning ()
 
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 ~ControllerBase ()
 

Private Member Functions

void complianceParamCallback (franka_example_controllers::compliance_paramConfig &config, uint32_t level)
 
void equilibriumPoseCallback (const geometry_msgs::PoseStampedConstPtr &msg)
 
Eigen::Matrix< double, 7, 1 > saturateTorqueRate (const Eigen::Matrix< double, 7, 1 > &tau_d_calculated, const Eigen::Matrix< double, 7, 1 > &tau_J_d)
 

Private Attributes

Eigen::Matrix< double, 6, 6 > cartesian_damping_
 
Eigen::Matrix< double, 6, 6 > cartesian_damping_target_
 
Eigen::Matrix< double, 6, 6 > cartesian_stiffness_
 
Eigen::Matrix< double, 6, 6 > cartesian_stiffness_target_
 
const double delta_tau_max_ {1.0}
 
ros::NodeHandle dynamic_reconfigure_compliance_param_node_
 
std::unique_ptr< dynamic_reconfigure::Server< franka_example_controllers::compliance_paramConfig > > dynamic_server_compliance_param_
 
double filter_params_ {0.005}
 
std::vector< hardware_interface::JointHandlejoint_handles_
 
std::unique_ptr< franka_hw::FrankaModelHandlemodel_handle_
 
double nullspace_stiffness_ {20.0}
 
double nullspace_stiffness_target_ {20.0}
 
Eigen::Quaterniond orientation_d_
 
Eigen::Quaterniond orientation_d_target_
 
Eigen::Vector3d position_d_
 
Eigen::Vector3d position_d_target_
 
Eigen::Matrix< double, 7, 1 > q_d_nullspace_
 
std::unique_ptr< franka_hw::FrankaStateHandlestate_handle_
 
ros::Subscriber sub_equilibrium_pose_
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
- Public Attributes inherited from controller_interface::ControllerBase
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  state_
 
- Protected Member Functions inherited from controller_interface::MultiInterfaceController< franka_hw::FrankaModelInterface, hardware_interface::EffortJointInterface, franka_hw::FrankaStateInterface >
virtual bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources)
 
- Static Protected Member Functions inherited from controller_interface::MultiInterfaceController< franka_hw::FrankaModelInterface, 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< franka_hw::FrankaModelInterface, hardware_interface::EffortJointInterface, franka_hw::FrankaStateInterface >
bool allow_optional_interfaces_
 
hardware_interface::RobotHW robot_hw_ctrl_
 

Detailed Description

Definition at line 24 of file cartesian_impedance_example_controller.h.

Member Function Documentation

void franka_example_controllers::CartesianImpedanceExampleController::complianceParamCallback ( franka_example_controllers::compliance_paramConfig &  config,
uint32_t  level 
)
private

Definition at line 212 of file cartesian_impedance_example_controller.cpp.

void franka_example_controllers::CartesianImpedanceExampleController::equilibriumPoseCallback ( const geometry_msgs::PoseStampedConstPtr &  msg)
private

Definition at line 229 of file cartesian_impedance_example_controller.cpp.

bool franka_example_controllers::CartesianImpedanceExampleController::init ( hardware_interface::RobotHW robot_hw,
ros::NodeHandle node_handle 
)
overridevirtual
Eigen::Matrix< double, 7, 1 > franka_example_controllers::CartesianImpedanceExampleController::saturateTorqueRate ( const Eigen::Matrix< double, 7, 1 > &  tau_d_calculated,
const Eigen::Matrix< double, 7, 1 > &  tau_J_d 
)
private

Definition at line 200 of file cartesian_impedance_example_controller.cpp.

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

Member Data Documentation

Eigen::Matrix<double, 6, 6> franka_example_controllers::CartesianImpedanceExampleController::cartesian_damping_
private

Definition at line 49 of file cartesian_impedance_example_controller.h.

Eigen::Matrix<double, 6, 6> franka_example_controllers::CartesianImpedanceExampleController::cartesian_damping_target_
private

Definition at line 50 of file cartesian_impedance_example_controller.h.

Eigen::Matrix<double, 6, 6> franka_example_controllers::CartesianImpedanceExampleController::cartesian_stiffness_
private

Definition at line 47 of file cartesian_impedance_example_controller.h.

Eigen::Matrix<double, 6, 6> franka_example_controllers::CartesianImpedanceExampleController::cartesian_stiffness_target_
private

Definition at line 48 of file cartesian_impedance_example_controller.h.

const double franka_example_controllers::CartesianImpedanceExampleController::delta_tau_max_ {1.0}
private

Definition at line 46 of file cartesian_impedance_example_controller.h.

ros::NodeHandle franka_example_controllers::CartesianImpedanceExampleController::dynamic_reconfigure_compliance_param_node_
private

Definition at line 60 of file cartesian_impedance_example_controller.h.

std::unique_ptr<dynamic_reconfigure::Server<franka_example_controllers::compliance_paramConfig> > franka_example_controllers::CartesianImpedanceExampleController::dynamic_server_compliance_param_
private

Definition at line 59 of file cartesian_impedance_example_controller.h.

double franka_example_controllers::CartesianImpedanceExampleController::filter_params_ {0.005}
private

Definition at line 43 of file cartesian_impedance_example_controller.h.

std::vector<hardware_interface::JointHandle> franka_example_controllers::CartesianImpedanceExampleController::joint_handles_
private

Definition at line 41 of file cartesian_impedance_example_controller.h.

std::unique_ptr<franka_hw::FrankaModelHandle> franka_example_controllers::CartesianImpedanceExampleController::model_handle_
private

Definition at line 40 of file cartesian_impedance_example_controller.h.

double franka_example_controllers::CartesianImpedanceExampleController::nullspace_stiffness_ {20.0}
private

Definition at line 44 of file cartesian_impedance_example_controller.h.

double franka_example_controllers::CartesianImpedanceExampleController::nullspace_stiffness_target_ {20.0}
private

Definition at line 45 of file cartesian_impedance_example_controller.h.

Eigen::Quaterniond franka_example_controllers::CartesianImpedanceExampleController::orientation_d_
private

Definition at line 53 of file cartesian_impedance_example_controller.h.

Eigen::Quaterniond franka_example_controllers::CartesianImpedanceExampleController::orientation_d_target_
private

Definition at line 55 of file cartesian_impedance_example_controller.h.

Eigen::Vector3d franka_example_controllers::CartesianImpedanceExampleController::position_d_
private

Definition at line 52 of file cartesian_impedance_example_controller.h.

Eigen::Vector3d franka_example_controllers::CartesianImpedanceExampleController::position_d_target_
private

Definition at line 54 of file cartesian_impedance_example_controller.h.

Eigen::Matrix<double, 7, 1> franka_example_controllers::CartesianImpedanceExampleController::q_d_nullspace_
private

Definition at line 51 of file cartesian_impedance_example_controller.h.

std::unique_ptr<franka_hw::FrankaStateHandle> franka_example_controllers::CartesianImpedanceExampleController::state_handle_
private

Definition at line 39 of file cartesian_impedance_example_controller.h.

ros::Subscriber franka_example_controllers::CartesianImpedanceExampleController::sub_equilibrium_pose_
private

Definition at line 65 of file cartesian_impedance_example_controller.h.


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


franka_example_controllers
Author(s): Franka Emika GmbH
autogenerated on Fri Oct 23 2020 03:47:17