Franky 0.12.0
A High-Level Motion API for Franka
|
Base class for client-side cartesian impedance motions. More...
#include <impedance_motion.hpp>
Classes | |
struct | Params |
Parameters for the impedance motion. More... | |
Public Member Functions | |
ImpedanceMotion (Affine target, const Params ¶ms) | |
![]() | |
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 |
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 |
virtual std::tuple< Affine, bool > | update (const RobotState &robot_state, franka::Duration time_step, franka::Duration time)=0 |
![]() | |
Motion () | |
Robot * | robot () const |
Additional Inherited Members | |
![]() | |
using | CallbackType = std::function< void(const RobotState &, franka::Duration, franka::Duration, franka::Duration, const franka::Torques &)> |
Base class for client-side cartesian impedance motions.
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.
target | The target pose. |
params | Parameters for the motion. |
|
overrideprotectedvirtual |
Reimplemented from franky::Motion< franka::Torques >.
|
inlineprotected |
|
overrideprotectedvirtual |
Implements franky::Motion< franka::Torques >.
|
inlineprotected |
|
protectedpure virtual |
Implemented in franky::CartesianImpedanceMotion, and franky::ExponentialImpedanceMotion.