3#include <franka/robot_state.h>
7#include <ruckig/ruckig.hpp>
42 const RobotState &robot_state,
const std::optional<franka::CartesianVelocities> &previous_command,
43 ruckig::InputParameter<7> &input_parameter)
override;
46 const RobotState &robot_state,
const std::optional<franka::CartesianVelocities> &previous_command,
52 const RobotState &robot_state,
const franka::Duration &time_step,
53 const std::optional<franka::CartesianVelocities> &previous_command,
54 const ruckig::InputParameter<7> &input_parameter)
override;
60 double last_elbow_pos_{};
61 double last_elbow_vel_{};
63 static Vector7d vec_cart_rot_elbow(
double cart,
double rot,
double elbow) {
64 return {cart, cart, cart, rot, rot, rot, elbow};
Cartesian velocity waypoint motion.
Definition cartesian_velocity_waypoint_motion.hpp:23
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
Definition cartesian_velocity_waypoint_motion.cpp:50
void checkWaypoint(const VelocityWaypoint< RobotVelocity > &waypoint) const override
Definition cartesian_velocity_waypoint_motion.cpp:17
void initWaypointMotion(const RobotState &robot_state, const std::optional< franka::CartesianVelocities > &previous_command, ruckig::InputParameter< 7 > &input_parameter) override
Definition cartesian_velocity_waypoint_motion.cpp:26
std::tuple< Vector7d, Vector7d, Vector7d > getAbsoluteInputLimits() const override
Definition cartesian_velocity_waypoint_motion.cpp:90
void setNewWaypoint(const RobotState &robot_state, const std::optional< franka::CartesianVelocities > &previous_command, const VelocityWaypoint< RobotVelocity > &new_waypoint, ruckig::InputParameter< 7 > &input_parameter) override
Definition cartesian_velocity_waypoint_motion.cpp:78
std::tuple< Vector7d, Vector7d, Vector7d > getDesiredState(const RobotState &robot_state) const override
Definition cartesian_velocity_waypoint_motion.cpp:102
Relative dynamics factors.
Definition relative_dynamics_factor.hpp:13
A motion following multiple positional waypoints in a time-optimal way. Works with arbitrary initial ...
Definition velocity_waypoint_motion.hpp:29
Definition dynamics_limit.cpp:8
Eigen::Vector< double, 7 > Vector7d
Definition types.hpp:11
Eigen::Affine3d Affine
Definition types.hpp:15
Full state of the robot.
Definition robot_state.hpp:23
A waypoint with a target and optional parameters.
Definition waypoint_motion.hpp:36