|
franky 1.1.2
A High-Level Motion API for Franka
|
Cartesian impedance motion. More...
#include <cartesian_impedance_motion.hpp>
Classes | |
| struct | Params |
| Parameters for the Cartesian impedance motion. More... | |
Public Member Functions | |
| CartesianImpedanceMotion (const Affine &target, franka::Duration duration) | |
| CartesianImpedanceMotion (const Affine &target, franka::Duration duration, const Params ¶ms) | |
Public Member Functions inherited from franky::ImpedanceMotion | |
| ImpedanceMotion (Affine target, const Params ¶ms) | |
Public Member Functions inherited from franky::Motion< franka::Torques > | |
| virtual | ~Motion ()=default |
| void | addReaction (std::shared_ptr< Reaction< franka::Torques > > reaction) |
| Add a reaction to the motion. | |
| void | addReactionFront (std::shared_ptr< Reaction< franka::Torques > > reaction) |
| Add a reaction to the front of the reaction list. | |
| std::vector< std::shared_ptr< Reaction< franka::Torques > > > | reactions () |
| Currently registered reactions of the motion. | |
| void | registerCallback (CallbackType callback) |
| Register a callback that is called in every step of the motion. | |
| void | init (Robot *robot, const RobotState &robot_state, const std::optional< franka::Torques > &previous_command) |
| Initialize the motion. | |
| franka::Torques | nextCommand (const RobotState &robot_state, franka::Duration time_step, franka::Duration rel_time, franka::Duration abs_time, const std::optional< franka::Torques > &previous_command) |
| Get the next command of the motion. | |
| std::shared_ptr< Motion< franka::Torques > > | checkAndCallReactions (const RobotState &robot_state, franka::Duration rel_time, franka::Duration abs_time) |
| Check and call reactions. | |
Protected Member Functions | |
| void | initImpl (const RobotState &robot_state, const std::optional< franka::Torques > &previous_command) override |
| std::tuple< Affine, bool > | update (const RobotState &robot_state, franka::Duration time_step, franka::Duration time) override |
Protected Member Functions inherited from franky::ImpedanceMotion | |
| void | initImpl (const RobotState &robot_state, const std::optional< franka::Torques > &previous_command) override |
| franka::Torques | nextCommandImpl (const RobotState &robot_state, franka::Duration time_step, franka::Duration rel_time, franka::Duration abs_time, const std::optional< franka::Torques > &previous_command) override |
| Affine | intermediate_target () const |
| Affine | target () const |
Protected Member Functions inherited from franky::Motion< franka::Torques > | |
| Motion () | |
| Robot * | robot () const |
Additional Inherited Members | |
Public Types inherited from franky::Motion< franka::Torques > | |
| using | CallbackType = std::function< void(const RobotState &, franka::Duration, franka::Duration, franka::Duration, const franka::Torques &)> |
Cartesian impedance motion.
This motion is a implements a cartesian impedance controller on the client side and does not use Franka's internal impedance controller. Instead, it uses Franka's internal torque controller and calculates the torques itself.
|
explicit |
| target | The target pose. |
| duration | The duration of the motion in [s]. |
|
explicit |
| target | The target pose. |
| duration | The duration of the motion in [s]. |
| params | Parameters for the motion. |
|
overrideprotectedvirtual |
Reimplemented from franky::Motion< franka::Torques >.
|
overrideprotectedvirtual |
Implements franky::ImpedanceMotion.