|
franky 1.1.2
A High-Level Motion API for Franka
|
Cartesian velocity motion with a single target velocity. More...
#include <cartesian_velocity_motion.hpp>
Public Member Functions | |
| CartesianVelocityMotion (const RobotVelocity &target, const franka::Duration &duration=franka::Duration(1000), const RelativeDynamicsFactor &relative_dynamics_factor=1.0, const Affine &frame=Affine::Identity()) | |
| Construct a Cartesian motion. | |
Public Member Functions inherited from franky::CartesianVelocityWaypointMotion | |
| 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. | |
Cartesian velocity motion with a single target velocity.
|
explicit |
Construct a Cartesian motion.
| target | The target Cartesian velocity. |
| duration | Duration this command is active. Default is 1s. |
| 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. |
| 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. |