|
| CartesianImpedanceMotion (const Affine &target, double duration) |
|
| CartesianImpedanceMotion (const Affine &target, double duration, const Params ¶ms) |
|
| ImpedanceMotion (Affine target, const Params ¶ms) |
|
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...
|
|
|
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 |
|
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 |
|
| Motion () |
|
Robot * | robot () const |
|
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.