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

Cartesian waypoint motion. More...

#include <cartesian_waypoint_motion.hpp>

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

Classes

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

Public Member Functions

 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...
 

Protected Member Functions

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
 

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 &)>
 

Detailed Description

Cartesian waypoint motion.

This motion follows multiple cartesian waypoints in a time-optimal way.

Constructor & Destructor Documentation

◆ CartesianWaypointMotion() [1/2]

franky::CartesianWaypointMotion::CartesianWaypointMotion ( const std::vector< Waypoint< CartesianState >> &  waypoints)
explicit
Parameters
waypointsWaypoints to follow.

◆ CartesianWaypointMotion() [2/2]

franky::CartesianWaypointMotion::CartesianWaypointMotion ( const std::vector< Waypoint< CartesianState >> &  waypoints,
Params  params 
)
explicit
Parameters
waypointsWaypoints to follow.
paramsParameters for the motion.

Member Function Documentation

◆ getAbsoluteInputLimits()

std::tuple< Vector7d, Vector7d, Vector7d > franky::CartesianWaypointMotion::getAbsoluteInputLimits ( ) const
overrideprotectedvirtual

◆ getControlSignal()

franka::CartesianPose franky::CartesianWaypointMotion::getControlSignal ( const ruckig::InputParameter< 7 > &  input_parameter) const
overrideprotectedvirtual

◆ initWaypointMotion()

void franky::CartesianWaypointMotion::initWaypointMotion ( const franka::RobotState &  robot_state,
const std::optional< franka::CartesianPose > &  previous_command,
ruckig::InputParameter< 7 > &  input_parameter 
)
overrideprotectedvirtual

◆ setNewWaypoint()

void franky::CartesianWaypointMotion::setNewWaypoint ( const franka::RobotState &  robot_state,
const std::optional< franka::CartesianPose > &  previous_command,
const Waypoint< CartesianState > &  new_waypoint,
ruckig::InputParameter< 7 > &  input_parameter 
)
overrideprotectedvirtual

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