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

Joint motion with a single target. More...

#include <joint_motion.hpp>

Inheritance diagram for franky::JointMotion:
franky::JointWaypointMotion franky::WaypointMotion< franka::JointPositions, JointState > franky::Motion< franka::JointPositions >

Public Member Functions

 JointMotion (const JointState &target, ReferenceType reference_type, RelativeDynamicsFactor relative_dynamics_factor, bool return_when_finished)
 
- Public Member Functions inherited from franky::JointWaypointMotion
 JointWaypointMotion (const std::vector< Waypoint< JointState >> &waypoints)
 
 JointWaypointMotion (const std::vector< Waypoint< JointState >> &waypoints, Params params)
 
- Public Member Functions inherited from franky::WaypointMotion< franka::JointPositions, JointState >
 WaypointMotion (std::vector< Waypoint< JointState >> waypoints, Params params)
 
- Public Member Functions inherited from franky::Motion< franka::JointPositions >
void addReaction (std::shared_ptr< Reaction< franka::JointPositions >> reaction)
 Add a reaction to the motion. More...
 
void addReactionFront (std::shared_ptr< Reaction< franka::JointPositions >> reaction)
 Add a reaction to the front of the reaction list. More...
 
std::vector< std::shared_ptr< Reaction< franka::JointPositions > > > 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::JointPositions > &previous_command)
 Initialize the motion. More...
 
franka::JointPositions nextCommand (const franka::RobotState &robot_state, franka::Duration time_step, double rel_time, double abs_time, const std::optional< franka::JointPositions > &previous_command)
 Get the next command of the motion. More...
 
std::shared_ptr< Motion< franka::JointPositions > > 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::JointPositions >
using CallbackType = std::function< void(const franka::RobotState &, franka::Duration, double, double, const franka::JointPositions &)>
 
- Protected Member Functions inherited from franky::JointWaypointMotion
void initWaypointMotion (const franka::RobotState &robot_state, const std::optional< franka::JointPositions > &previous_command, ruckig::InputParameter< 7 > &input_parameter) override
 
void setNewWaypoint (const franka::RobotState &robot_state, const std::optional< franka::JointPositions > &previous_command, const Waypoint< JointState > &new_waypoint, ruckig::InputParameter< 7 > &input_parameter) override
 
std::tuple< Vector7d, Vector7d, Vector7dgetAbsoluteInputLimits () const override
 
franka::JointPositions getControlSignal (const ruckig::InputParameter< 7 > &input_parameter) const override
 
- Protected Member Functions inherited from franky::WaypointMotion< franka::JointPositions, JointState >
void initImpl (const franka::RobotState &robot_state, const std::optional< franka::JointPositions > &previous_command) override
 
franka::JointPositions nextCommandImpl (const franka::RobotState &robot_state, franka::Duration time_step, double rel_time, double abs_time, const std::optional< franka::JointPositions > &previous_command) override
 
- Protected Member Functions inherited from franky::Motion< franka::JointPositions >
 Motion ()
 
Robotrobot () const
 

Detailed Description

Joint motion with a single target.

Constructor & Destructor Documentation

◆ JointMotion()

franky::JointMotion::JointMotion ( const JointState target,
ReferenceType  reference_type,
RelativeDynamicsFactor  relative_dynamics_factor,
bool  return_when_finished 
)
explicit
Parameters
targetThe target joint state.
reference_typeThe reference type (absolute or relative). An absolute target describes the actual target joint positions, a relative target describes the target joint positions relative to the current joint positions.
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: