|
franky 1.1.2
A High-Level Motion API for Franka
|
Cartesian motion with a single target. More...
#include <cartesian_motion.hpp>
Public Member Functions | |
| CartesianMotion (const CartesianState &target, 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. | |
Cartesian motion with a single target.
|
explicit |
Construct a Cartesian motion.
| target | The target Cartesian state. |
| reference_type | The 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_factor | The 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_finished | Whether to end the motion when the target is reached or keep holding the last target. |
| frame | The 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. |