Franky 0.12.0
A High-Level Motion API for Franka
Loading...
Searching...
No Matches
Public Member Functions | Protected Member Functions | List of all members
franky::CartesianVelocityWaypointMotion Class Reference

Cartesian velocity waypoint motion. More...

#include <cartesian_velocity_waypoint_motion.hpp>

Inheritance diagram for franky::CartesianVelocityWaypointMotion:
franky::VelocityWaypointMotion< franka::CartesianVelocities, RobotVelocity > franky::WaypointMotion< ControlSignalType, WaypointType, TargetType > franky::Motion< ControlSignalType > franky::CartesianVelocityMotion franky::StopMotion< franka::CartesianVelocities >

Public Member Functions

 CartesianVelocityWaypointMotion (const std::vector< VelocityWaypoint< RobotVelocity > > &waypoints, const RelativeDynamicsFactor &relative_dynamics_factor=1.0, Affine ee_frame=Affine::Identity())
 
- Public Member Functions inherited from franky::VelocityWaypointMotion< franka::CartesianVelocities, RobotVelocity >
 VelocityWaypointMotion (std::vector< VelocityWaypoint< RobotVelocity > > waypoints, const RelativeDynamicsFactor &relative_dynamics_factor=1.0)
 
- Public Member Functions inherited from franky::WaypointMotion< ControlSignalType, WaypointType, TargetType >
 WaypointMotion (std::vector< WaypointType > waypoints, bool return_when_finished=true)
 
- Public Member Functions inherited from franky::Motion< ControlSignalType >
virtual ~Motion ()=default
 
void addReaction (std::shared_ptr< Reaction< ControlSignalType > > reaction)
 Add a reaction to the motion.
 
void addReactionFront (std::shared_ptr< Reaction< ControlSignalType > > reaction)
 Add a reaction to the front of the reaction list.
 
std::vector< std::shared_ptr< Reaction< ControlSignalType > > > 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< ControlSignalType > &previous_command)
 Initialize the motion.
 
ControlSignalType nextCommand (const RobotState &robot_state, franka::Duration time_step, franka::Duration rel_time, franka::Duration abs_time, const std::optional< ControlSignalType > &previous_command)
 Get the next command of the motion.
 
std::shared_ptr< Motion< ControlSignalType > > checkAndCallReactions (const RobotState &robot_state, franka::Duration rel_time, franka::Duration abs_time)
 Check and call reactions.
 

Protected Member Functions

void checkWaypoint (const VelocityWaypoint< RobotVelocity > &waypoint) const override
 
void initWaypointMotion (const RobotState &robot_state, const std::optional< franka::CartesianVelocities > &previous_command, ruckig::InputParameter< 7 > &input_parameter) override
 
void setNewWaypoint (const RobotState &robot_state, const std::optional< franka::CartesianVelocities > &previous_command, const VelocityWaypoint< RobotVelocity > &new_waypoint, ruckig::InputParameter< 7 > &input_parameter) override
 
std::tuple< Vector7d, Vector7d, Vector7dgetAbsoluteInputLimits () const override
 
franka::CartesianVelocities getControlSignal (const RobotState &robot_state, const franka::Duration &time_step, const std::optional< franka::CartesianVelocities > &previous_command, const ruckig::InputParameter< 7 > &input_parameter) override
 
virtual std::tuple< Vector7d, Vector7d, Vector7dgetStateEstimate (const RobotState &robot_state) const override
 
- Protected Member Functions inherited from franky::VelocityWaypointMotion< franka::CartesianVelocities, RobotVelocity >
void setInputLimits (const VelocityWaypoint< RobotVelocity > &waypoint, ruckig::InputParameter< 7 > &input_parameter) const override
 
void extrapolateMotion (const franka::Duration &time_step, const ruckig::InputParameter< 7 > &input_parameter, ruckig::OutputParameter< 7 > &output_parameter) const override
 
- Protected Member Functions inherited from franky::WaypointMotion< ControlSignalType, WaypointType, TargetType >
void initImpl (const RobotState &robot_state, const std::optional< ControlSignalType > &previous_command) override
 
ControlSignalType nextCommandImpl (const RobotState &robot_state, franka::Duration time_step, franka::Duration rel_time, franka::Duration abs_time, const std::optional< ControlSignalType > &previous_command) override
 
virtual void initWaypointMotion (const RobotState &robot_state, const std::optional< ControlSignalType > &previous_command, ruckig::InputParameter< 7 > &input_parameter)=0
 
virtual void setNewWaypoint (const RobotState &robot_state, const std::optional< ControlSignalType > &previous_command, const WaypointType &new_waypoint, ruckig::InputParameter< 7 > &input_parameter)=0
 
virtual void checkWaypoint (const WaypointType &waypoint) const
 
virtual ControlSignalType getControlSignal (const RobotState &robot_state, const franka::Duration &time_step, const std::optional< ControlSignalType > &previous_command, const ruckig::InputParameter< 7 > &input_parameter)=0
 
virtual void setInputLimits (const WaypointType &waypoint, ruckig::InputParameter< 7 > &input_parameter) const =0
 
- Protected Member Functions inherited from franky::Motion< ControlSignalType >
 Motion ()
 
Robotrobot () const
 

Additional Inherited Members

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

Detailed Description

Cartesian velocity waypoint motion.

This motion follows multiple consecutive cartesian velocity targets in a time-optimal way.

Constructor & Destructor Documentation

◆ CartesianVelocityWaypointMotion()

franky::CartesianVelocityWaypointMotion::CartesianVelocityWaypointMotion ( const std::vector< VelocityWaypoint< RobotVelocity > > &  waypoints,
const RelativeDynamicsFactor relative_dynamics_factor = 1.0,
Affine  ee_frame = Affine::Identity() 
)
explicit
Parameters
waypointsWaypoints to follow.
relative_dynamics_factorThe relative dynamics factor for this motion. This factor will get multiplied with the robot's global dynamics factor to get the actual dynamics factor for this motion.
ee_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.

Member Function Documentation

◆ checkWaypoint()

void franky::CartesianVelocityWaypointMotion::checkWaypoint ( const VelocityWaypoint< RobotVelocity > &  waypoint) const
overrideprotected

◆ getAbsoluteInputLimits()

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

◆ getControlSignal()

franka::CartesianVelocities franky::CartesianVelocityWaypointMotion::getControlSignal ( const RobotState robot_state,
const franka::Duration &  time_step,
const std::optional< franka::CartesianVelocities > &  previous_command,
const ruckig::InputParameter< 7 > &  input_parameter 
)
overrideprotected

◆ getStateEstimate()

std::tuple< Vector7d, Vector7d, Vector7d > franky::CartesianVelocityWaypointMotion::getStateEstimate ( const RobotState robot_state) const
overrideprotectedvirtual

◆ initWaypointMotion()

void franky::CartesianVelocityWaypointMotion::initWaypointMotion ( const RobotState robot_state,
const std::optional< franka::CartesianVelocities > &  previous_command,
ruckig::InputParameter< 7 > &  input_parameter 
)
overrideprotected

◆ setNewWaypoint()

void franky::CartesianVelocityWaypointMotion::setNewWaypoint ( const RobotState robot_state,
const std::optional< franka::CartesianVelocities > &  previous_command,
const VelocityWaypoint< RobotVelocity > &  new_waypoint,
ruckig::InputParameter< 7 > &  input_parameter 
)
overrideprotected

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