Public Attributes | List of all members
franka_example_controllers::FrankaDataContainer Struct Reference

This container holds all data and parameters used to control one panda arm with a Cartesian impedance control law tracking a desired target pose. More...

#include <dual_arm_cartesian_impedance_example_controller.h>

Public Attributes

Eigen::Matrix< double, 6, 6 > cartesian_damping_
 To damp cartesian motions. More...
 
Eigen::Matrix< double, 6, 6 > cartesian_damping_target_
 Unfiltered raw value. More...
 
Eigen::Matrix< double, 6, 6 > cartesian_stiffness_
 To track the target pose. More...
 
Eigen::Matrix< double, 6, 6 > cartesian_stiffness_target_
 Unfiltered raw value. More...
 
const double delta_tau_max_ {1.0}
 [Nm/ms] Maximum difference in joint-torque per timestep. More...
 
double filter_params_ {0.005}
 [-] PT1-Filter constant to smooth target values set by dynamic reconfigure servers (stiffness/damping) or interactive markers for the target poses. More...
 
std::vector< hardware_interface::JointHandlejoint_handles_
 To command joint torques. More...
 
std::unique_ptr< franka_hw::FrankaModelHandlemodel_handle_
 To have access to e.g. jacobians. More...
 
double nullspace_stiffness_ {20.0}
 [Nm/rad] To track the initial joint configuration in the nullspace of the Cartesian motion. More...
 
double nullspace_stiffness_target_ {20.0}
 [Nm/rad] Unfiltered raw value. More...
 
Eigen::Quaterniond orientation_d_
 Target orientation of the end effector. More...
 
Eigen::Quaterniond orientation_d_target_
 Unfiltered raw value. More...
 
Eigen::Vector3d position_d_
 Target position of the end effector. More...
 
Eigen::Vector3d position_d_target_
 Unfiltered raw value. More...
 
Eigen::Matrix< double, 7, 1 > q_d_nullspace_
 Target joint pose for nullspace motion. More...
 
std::unique_ptr< franka_hw::FrankaStateHandlestate_handle_
 To read to complete robot state. More...
 

Detailed Description

This container holds all data and parameters used to control one panda arm with a Cartesian impedance control law tracking a desired target pose.

Definition at line 30 of file dual_arm_cartesian_impedance_example_controller.h.

Member Data Documentation

Eigen::Matrix<double, 6, 6> franka_example_controllers::FrankaDataContainer::cartesian_damping_

To damp cartesian motions.

Definition at line 47 of file dual_arm_cartesian_impedance_example_controller.h.

Eigen::Matrix<double, 6, 6> franka_example_controllers::FrankaDataContainer::cartesian_damping_target_

Unfiltered raw value.

Definition at line 48 of file dual_arm_cartesian_impedance_example_controller.h.

Eigen::Matrix<double, 6, 6> franka_example_controllers::FrankaDataContainer::cartesian_stiffness_

To track the target pose.

Definition at line 45 of file dual_arm_cartesian_impedance_example_controller.h.

Eigen::Matrix<double, 6, 6> franka_example_controllers::FrankaDataContainer::cartesian_stiffness_target_

Unfiltered raw value.

Definition at line 46 of file dual_arm_cartesian_impedance_example_controller.h.

const double franka_example_controllers::FrankaDataContainer::delta_tau_max_ {1.0}

[Nm/ms] Maximum difference in joint-torque per timestep.

Used to saturated torque rates to ensure feasible commands.

Definition at line 42 of file dual_arm_cartesian_impedance_example_controller.h.

double franka_example_controllers::FrankaDataContainer::filter_params_ {0.005}

[-] PT1-Filter constant to smooth target values set by dynamic reconfigure servers (stiffness/damping) or interactive markers for the target poses.

Definition at line 36 of file dual_arm_cartesian_impedance_example_controller.h.

std::vector<hardware_interface::JointHandle> franka_example_controllers::FrankaDataContainer::joint_handles_

To command joint torques.

Definition at line 35 of file dual_arm_cartesian_impedance_example_controller.h.

std::unique_ptr<franka_hw::FrankaModelHandle> franka_example_controllers::FrankaDataContainer::model_handle_

To have access to e.g. jacobians.

Definition at line 34 of file dual_arm_cartesian_impedance_example_controller.h.

double franka_example_controllers::FrankaDataContainer::nullspace_stiffness_ {20.0}

[Nm/rad] To track the initial joint configuration in the nullspace of the Cartesian motion.

Definition at line 39 of file dual_arm_cartesian_impedance_example_controller.h.

double franka_example_controllers::FrankaDataContainer::nullspace_stiffness_target_ {20.0}

[Nm/rad] Unfiltered raw value.

Definition at line 41 of file dual_arm_cartesian_impedance_example_controller.h.

Eigen::Quaterniond franka_example_controllers::FrankaDataContainer::orientation_d_

Target orientation of the end effector.

Definition at line 53 of file dual_arm_cartesian_impedance_example_controller.h.

Eigen::Quaterniond franka_example_controllers::FrankaDataContainer::orientation_d_target_

Unfiltered raw value.

Definition at line 55 of file dual_arm_cartesian_impedance_example_controller.h.

Eigen::Vector3d franka_example_controllers::FrankaDataContainer::position_d_

Target position of the end effector.

Definition at line 52 of file dual_arm_cartesian_impedance_example_controller.h.

Eigen::Vector3d franka_example_controllers::FrankaDataContainer::position_d_target_

Unfiltered raw value.

Definition at line 54 of file dual_arm_cartesian_impedance_example_controller.h.

Eigen::Matrix<double, 7, 1> franka_example_controllers::FrankaDataContainer::q_d_nullspace_

Target joint pose for nullspace motion.

For now we track the initial joint pose.

Definition at line 49 of file dual_arm_cartesian_impedance_example_controller.h.

std::unique_ptr<franka_hw::FrankaStateHandle> franka_example_controllers::FrankaDataContainer::state_handle_

To read to complete robot state.

Definition at line 32 of file dual_arm_cartesian_impedance_example_controller.h.


The documentation for this struct was generated from the following file:


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