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

Cartesian motion with a single target. More...

#include <cartesian_motion.hpp>

Inheritance diagram for franky::CartesianMotion:
franky::CartesianWaypointMotion franky::WaypointMotion< franka::CartesianPose, CartesianState > franky::Motion< franka::CartesianPose >

Public Member Functions

 CartesianMotion (const CartesianState &target, ReferenceType reference_type=ReferenceType::Absolute, const Affine &frame=Affine::Identity(), RelativeDynamicsFactor relative_dynamics_factor=1.0, bool return_when_finished=true)
 Construct a Cartesian motion. More...
 
- Public Member Functions inherited from franky::CartesianWaypointMotion
 CartesianWaypointMotion (const std::vector< Waypoint< CartesianState >> &waypoints)
 
 CartesianWaypointMotion (const std::vector< Waypoint< CartesianState >> &waypoints, Params params)
 
- Public Member Functions inherited from franky::WaypointMotion< franka::CartesianPose, CartesianState >
 WaypointMotion (std::vector< Waypoint< CartesianState >> waypoints, Params params)
 
- Public Member Functions inherited from franky::Motion< franka::CartesianPose >
void addReaction (std::shared_ptr< Reaction< franka::CartesianPose >> reaction)
 Add a reaction to the motion. More...
 
void addReactionFront (std::shared_ptr< Reaction< franka::CartesianPose >> reaction)
 Add a reaction to the front of the reaction list. More...
 
std::vector< std::shared_ptr< Reaction< franka::CartesianPose > > > 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::CartesianPose > &previous_command)
 Initialize the motion. More...
 
franka::CartesianPose nextCommand (const franka::RobotState &robot_state, franka::Duration time_step, double rel_time, double abs_time, const std::optional< franka::CartesianPose > &previous_command)
 Get the next command of the motion. More...
 
std::shared_ptr< Motion< franka::CartesianPose > > checkAndCallReactions (const franka::RobotState &robot_state, double rel_time, double abs_time)
 Check and call reactions. More...
 

Additional Inherited Members

- Public Types inherited from franky::Motion< franka::CartesianPose >
using CallbackType = std::function< void(const franka::RobotState &, franka::Duration, double, double, const franka::CartesianPose &)>
 
- Protected Member Functions inherited from franky::CartesianWaypointMotion
void initWaypointMotion (const franka::RobotState &robot_state, const std::optional< franka::CartesianPose > &previous_command, ruckig::InputParameter< 7 > &input_parameter) override
 
void setNewWaypoint (const franka::RobotState &robot_state, const std::optional< franka::CartesianPose > &previous_command, const Waypoint< CartesianState > &new_waypoint, ruckig::InputParameter< 7 > &input_parameter) override
 
std::tuple< Vector7d, Vector7d, Vector7dgetAbsoluteInputLimits () const override
 
franka::CartesianPose getControlSignal (const ruckig::InputParameter< 7 > &input_parameter) const override
 
- Protected Member Functions inherited from franky::WaypointMotion< franka::CartesianPose, CartesianState >
void initImpl (const franka::RobotState &robot_state, const std::optional< franka::CartesianPose > &previous_command) override
 
franka::CartesianPose nextCommandImpl (const franka::RobotState &robot_state, franka::Duration time_step, double rel_time, double abs_time, const std::optional< franka::CartesianPose > &previous_command) override
 
- Protected Member Functions inherited from franky::Motion< franka::CartesianPose >
 Motion ()
 
Robotrobot () const
 

Detailed Description

Cartesian motion with a single target.

Constructor & Destructor Documentation

◆ CartesianMotion()

franky::CartesianMotion::CartesianMotion ( const CartesianState target,
ReferenceType  reference_type = ReferenceType::Absolute,
const Affine frame = Affine::Identity(),
RelativeDynamicsFactor  relative_dynamics_factor = 1.0,
bool  return_when_finished = true 
)
explicit

Construct a Cartesian motion.

Parameters
targetThe target Cartesian state.
reference_typeThe reference type (absolute or relative). An absolute target is defined in the robot's base frame, a relative target is defined in the current end-effector frame.
frameThe end-effector frame for which the target is defined. This is a transformation from the configured end-effector frame to the end-effector frame the target is defined for.
relative_dynamics_factorThe relative dynamics factor for this motion. The factor will get multiplied with the robot's global dynamics factor to get the actual dynamics factor for this motion.
return_when_finishedWhether to end the motion when the target is reached or keep holding the last target.

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