#include <joint_impedance_example_controller.h>
|
| std::array< double, 7 > | saturateTorqueRate (const std::array< double, 7 > &tau_d_calculated, const std::array< double, 7 > &tau_J_d) |
| |
|
| typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
| |
| enum | ControllerState {
ControllerState::CONSTRUCTED,
ControllerState::INITIALIZED,
ControllerState::RUNNING,
ControllerState::STOPPED,
ControllerState::WAITING,
ControllerState::ABORTED
} |
| |
| ControllerState | state_ |
| |
| bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override |
| |
| 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) |
| |
| bool | allow_optional_interfaces_ |
| |
| hardware_interface::RobotHW | robot_hw_ctrl_ |
| |
◆ init()
◆ saturateTorqueRate()
| std::array< double, 7 > franka_example_controllers::JointImpedanceExampleController::saturateTorqueRate |
( |
const std::array< double, 7 > & |
tau_d_calculated, |
|
|
const std::array< double, 7 > & |
tau_J_d |
|
) |
| |
|
private |
◆ starting()
| void franka_example_controllers::JointImpedanceExampleController::starting |
( |
const ros::Time & |
| ) |
|
|
overridevirtual |
◆ update()
| void franka_example_controllers::JointImpedanceExampleController::update |
( |
const ros::Time & |
, |
|
|
const ros::Duration & |
period |
|
) |
| |
|
overridevirtual |
◆ acceleration_time_
| double franka_example_controllers::JointImpedanceExampleController::acceleration_time_ {2.0} |
|
private |
◆ angle_
| double franka_example_controllers::JointImpedanceExampleController::angle_ {0.0} |
|
private |
◆ cartesian_pose_handle_
◆ coriolis_factor_
| double franka_example_controllers::JointImpedanceExampleController::coriolis_factor_ {1.0} |
|
private |
◆ d_gains_
| std::vector<double> franka_example_controllers::JointImpedanceExampleController::d_gains_ |
|
private |
◆ dq_filtered_
| std::array<double, 7> franka_example_controllers::JointImpedanceExampleController::dq_filtered_ |
|
private |
◆ initial_pose_
| std::array<double, 16> franka_example_controllers::JointImpedanceExampleController::initial_pose_ |
|
private |
◆ joint_handles_
◆ k_gains_
| std::vector<double> franka_example_controllers::JointImpedanceExampleController::k_gains_ |
|
private |
◆ kDeltaTauMax
| constexpr double franka_example_controllers::JointImpedanceExampleController::kDeltaTauMax {1.0} |
|
staticconstexprprivate |
◆ last_tau_d_
| std::array<double, 7> franka_example_controllers::JointImpedanceExampleController::last_tau_d_ {} |
|
private |
◆ model_handle_
◆ radius_
| double franka_example_controllers::JointImpedanceExampleController::radius_ {0.1} |
|
private |
◆ rate_trigger_
◆ torques_publisher_
◆ vel_current_
| double franka_example_controllers::JointImpedanceExampleController::vel_current_ {0.0} |
|
private |
◆ vel_max_
| double franka_example_controllers::JointImpedanceExampleController::vel_max_ {0.05} |
|
private |
The documentation for this class was generated from the following files: