|
Haptic Controller
|
Go to the source code of this file.
Functions | |
| std::vector< float > | forward_kinematics (std::vector< float > joint_angles) |
| Performs forward kinematics for the haptic finger. | |
| std::vector< float > | inverse_kinematics (std::vector< float > pos) |
| Performs inverse kinematics for the haptic finger. | |
| std::vector< float > | motors_to_joints (std::vector< float > motor_vars) |
| std::vector< float > | joints_to_motors (std::vector< float > joint_vars) |
| std::vector< float > | phi_to_theta (std::vector< float > motor_phis) |
| std::vector< float > | theta_to_phi (std::vector< float > joint_thetas) |
| std::vector< float > | tau_to_torque (std::vector< float > joint_taus) |
| std::vector< float > | torque_to_tau (std::vector< float > motor_torques) |
| Matrix | spatial_jacobian (std::vector< float > joint_angles) |
| std::vector< float > | soft_limit_torques (std::vector< float > joint_thetas) |
| std::vector< float > forward_kinematics | ( | std::vector< float > | joint_angles | ) |
Performs forward kinematics for the haptic finger.
| joint_angles | - {theta_0, theta_1} in radians for the joints. |
Definition at line 64 of file haptic_finger.hpp.
Referenced by updateAndSendSystemInfo().
| std::vector< float > inverse_kinematics | ( | std::vector< float > | pos | ) |
Performs inverse kinematics for the haptic finger.
| pos | {x, y, z} in meters of the end effector. |
Definition at line 82 of file haptic_finger.hpp.
References pos.
| std::vector< float > joints_to_motors | ( | std::vector< float > | joint_vars | ) |
Definition at line 104 of file haptic_finger.hpp.
Referenced by theta_to_phi().
| std::vector< float > motors_to_joints | ( | std::vector< float > | motor_vars | ) |
Definition at line 95 of file haptic_finger.hpp.
Referenced by phi_to_theta(), and updateAndSendSystemInfo().
| std::vector< float > phi_to_theta | ( | std::vector< float > | motor_phis | ) |
Definition at line 114 of file haptic_finger.hpp.
References joint_thetas, and motors_to_joints().
Referenced by updateAndSendSystemInfo().
| std::vector< float > soft_limit_torques | ( | std::vector< float > | joint_thetas | ) |
Definition at line 169 of file haptic_finger.hpp.
References joint_thetas, and Limits< T >::over_limits().
Referenced by endEffMirrorUpdate(), and jointMirrorUpdate().
| Matrix spatial_jacobian | ( | std::vector< float > | joint_angles | ) |
Definition at line 152 of file haptic_finger.hpp.
Referenced by endEffMirrorUpdate(), and updateAndSendSystemInfo().
| std::vector< float > tau_to_torque | ( | std::vector< float > | joint_taus | ) |
Definition at line 130 of file haptic_finger.hpp.
Referenced by endEffMirrorUpdate(), and jointMirrorUpdate().
| std::vector< float > theta_to_phi | ( | std::vector< float > | joint_thetas | ) |
Definition at line 122 of file haptic_finger.hpp.
References joint_thetas, and joints_to_motors().
| std::vector< float > torque_to_tau | ( | std::vector< float > | motor_torques | ) |
Definition at line 141 of file haptic_finger.hpp.