Franky 0.12.0
A High-Level Motion API for Franka
Loading...
Searching...
No Matches
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::PositionWaypointMotion< franka::CartesianPose, CartesianState > franky::WaypointMotion< ControlSignalType, WaypointType, TargetType > franky::Motion< ControlSignalType >

Public Member Functions

 CartesianMotion (const CartesianState &target, double state_estimate_weight=0.0, ReferenceType reference_type=ReferenceType::kAbsolute, const RelativeDynamicsFactor &relative_dynamics_factor=1.0, bool return_when_finished=true, const Affine &frame=Affine::Identity())
 Construct a Cartesian motion.
 
- Public Member Functions inherited from franky::CartesianWaypointMotion
 CartesianWaypointMotion (const std::vector< PositionWaypoint< CartesianState > > &waypoints, const RelativeDynamicsFactor &relative_dynamics_factor=1.0, bool return_when_finished=true, Affine ee_frame=Affine::Identity())
 
- Public Member Functions inherited from franky::PositionWaypointMotion< franka::CartesianPose, CartesianState >
 PositionWaypointMotion (std::vector< PositionWaypoint< CartesianState > > waypoints, const RelativeDynamicsFactor &relative_dynamics_factor=1.0, bool return_when_finished=true)
 
- 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.
 

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 &)>
 
- Protected Member Functions inherited from franky::CartesianWaypointMotion
void initWaypointMotion (const RobotState &robot_state, const std::optional< franka::CartesianPose > &previous_command, ruckig::InputParameter< 7 > &input_parameter) override
 
void setNewWaypoint (const RobotState &robot_state, const std::optional< franka::CartesianPose > &previous_command, const PositionWaypoint< CartesianState > &new_waypoint, ruckig::InputParameter< 7 > &input_parameter) override
 
std::tuple< Vector7d, Vector7d, Vector7dgetAbsoluteInputLimits () const override
 
franka::CartesianPose getControlSignal (const RobotState &robot_state, const franka::Duration &time_step, const std::optional< franka::CartesianPose > &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::PositionWaypointMotion< franka::CartesianPose, CartesianState >
void setInputLimits (const PositionWaypoint< CartesianState > &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
 

Detailed Description

Cartesian motion with a single target.

Constructor & Destructor Documentation

◆ CartesianMotion()

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

Construct a Cartesian motion.

Parameters
targetThe target Cartesian state.
state_estimate_weightWeighting of the robot state estimate vs the target when computing the current state to continue planning from. A value of 0 means that the planner always assumes it reached its last target perfectly (open loop control), while a value of 1 means that the planner always uses the robot state estimate (closed loop control). A value between 0 and 1 means that the planner uses a weighted average of the two.
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.
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.
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.

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