Franky  0.9.1
A High-Level Motion API for Franka
Classes | Public Member Functions | Protected Member Functions | List of all members
franky::CartesianImpedanceMotion Class Reference

Cartesian impedance motion. More...

#include <cartesian_impedance_motion.hpp>

Inheritance diagram for franky::CartesianImpedanceMotion:
franky::ImpedanceMotion franky::Motion< franka::Torques >

Classes

struct  Params
 Parameters for the Cartesian impedance motion. More...
 

Public Member Functions

 CartesianImpedanceMotion (const Affine &target, double duration)
 
 CartesianImpedanceMotion (const Affine &target, double duration, const Params &params)
 
- Public Member Functions inherited from franky::ImpedanceMotion
 ImpedanceMotion (Affine target, const Params &params)
 
- Public Member Functions inherited from franky::Motion< franka::Torques >
void addReaction (std::shared_ptr< Reaction< franka::Torques >> reaction)
 Add a reaction to the motion. More...
 
void addReactionFront (std::shared_ptr< Reaction< franka::Torques >> reaction)
 Add a reaction to the front of the reaction list. More...
 
std::vector< std::shared_ptr< Reaction< franka::Torques > > > reactions ()
 Currently registered reactions of the motion. More...
 
void registerCallback (CallbackType callback)
 Register a callback that is called in every step of the motion. More...
 
void init (Robot *robot, const franka::RobotState &robot_state, const std::optional< franka::Torques > &previous_command)
 Initialize the motion. More...
 
franka::Torques nextCommand (const franka::RobotState &robot_state, franka::Duration time_step, double rel_time, double abs_time, const std::optional< franka::Torques > &previous_command)
 Get the next command of the motion. More...
 
std::shared_ptr< Motion< franka::Torques > > checkAndCallReactions (const franka::RobotState &robot_state, double rel_time, double abs_time)
 Check and call reactions. More...
 

Protected Member Functions

void initImpl (const franka::RobotState &robot_state, const std::optional< franka::Torques > &previous_command) override
 
std::tuple< Affine, bool > update (const franka::RobotState &robot_state, franka::Duration time_step, double time) override
 
- Protected Member Functions inherited from franky::ImpedanceMotion
void initImpl (const franka::RobotState &robot_state, const std::optional< franka::Torques > &previous_command) override
 
franka::Torques nextCommandImpl (const franka::RobotState &robot_state, franka::Duration time_step, double rel_time, double 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 ()
 
Robotrobot () const
 

Additional Inherited Members

- Public Types inherited from franky::Motion< franka::Torques >
using CallbackType = std::function< void(const franka::RobotState &, franka::Duration, double, double, const franka::Torques &)>
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ CartesianImpedanceMotion() [1/2]

franky::CartesianImpedanceMotion::CartesianImpedanceMotion ( const Affine target,
double  duration 
)
explicit
Parameters
targetThe target pose.
durationThe duration of the motion in [s].

◆ CartesianImpedanceMotion() [2/2]

franky::CartesianImpedanceMotion::CartesianImpedanceMotion ( const Affine target,
double  duration,
const Params params 
)
explicit
Parameters
targetThe target pose.
durationThe duration of the motion in [s].
paramsParameters for the motion.

Member Function Documentation

◆ initImpl()

void franky::CartesianImpedanceMotion::initImpl ( const franka::RobotState &  robot_state,
const std::optional< franka::Torques > &  previous_command 
)
overrideprotectedvirtual

Reimplemented from franky::Motion< franka::Torques >.

◆ update()

std::tuple< Affine, bool > franky::CartesianImpedanceMotion::update ( const franka::RobotState &  robot_state,
franka::Duration  time_step,
double  time 
)
overrideprotectedvirtual

The documentation for this class was generated from the following files: