5 #include <ruckig/ruckig.hpp>
7 #include <franka/robot_state.h>
50 const franka::RobotState &robot_state,
51 const std::optional<franka::CartesianPose> &previous_command,
52 ruckig::InputParameter<7> &input_parameter)
override;
55 const franka::RobotState &robot_state,
56 const std::optional<franka::CartesianPose> &previous_command,
58 ruckig::InputParameter<7> &input_parameter)
override;
70 static inline Vector7d vec_cart_rot_elbow(
double cart,
double rot,
double elbow) {
71 return {cart, cart, cart, rot, rot, rot, elbow};
Definition: cartesian_state.hpp:17
Cartesian waypoint motion.
Definition: cartesian_waypoint_motion.hpp:23
void initWaypointMotion(const franka::RobotState &robot_state, const std::optional< franka::CartesianPose > &previous_command, ruckig::InputParameter< 7 > &input_parameter) override
Definition: cartesian_waypoint_motion.cpp:19
CartesianWaypointMotion(const std::vector< Waypoint< CartesianState >> &waypoints)
Definition: cartesian_waypoint_motion.cpp:12
std::tuple< Vector7d, Vector7d, Vector7d > getAbsoluteInputLimits() const override
Definition: cartesian_waypoint_motion.cpp:117
franka::CartesianPose getControlSignal(const ruckig::InputParameter< 7 > &input_parameter) const override
Definition: cartesian_waypoint_motion.cpp:38
void setNewWaypoint(const franka::RobotState &robot_state, const std::optional< franka::CartesianPose > &previous_command, const Waypoint< CartesianState > &new_waypoint, ruckig::InputParameter< 7 > &input_parameter) override
Definition: cartesian_waypoint_motion.cpp:44
A motion following multiple waypoints in a time-optimal way. Works with arbitrary initial conditions.
Definition: waypoint_motion.hpp:51
Definition: gripper.cpp:3
Eigen::Vector< double, 7 > Vector7d
Definition: types.hpp:9
@ CartesianPose
Definition: control_signal_type.hpp:13
Eigen::Affine3d Affine
Definition: types.hpp:13
Parameters for the Cartesian waypoint motion.
Definition: cartesian_waypoint_motion.hpp:29
Affine frame
Definition: cartesian_waypoint_motion.hpp:34
A waypoint with a target and optional parameters.
Definition: waypoint_motion.hpp:34