3#include <franka/robot_state.h>
7#include <ruckig/ruckig.hpp>
40 Affine ee_frame = Affine::Identity());
44 const RobotState &robot_state,
const std::optional<franka::CartesianPose> &previous_command,
45 ruckig::InputParameter<7> &input_parameter)
override;
48 const RobotState &robot_state,
const std::optional<franka::CartesianPose> &previous_command,
54 const RobotState &robot_state,
const franka::Duration &time_step,
55 const std::optional<franka::CartesianPose> &previous_command,
56 const ruckig::InputParameter<7> &input_parameter)
override;
65 static Vector7d vec_cart_rot_elbow(
double cart,
double rot,
double elbow) {
66 return {cart, cart, cart, rot, rot, rot, elbow};
Definition cartesian_state.hpp:17
Cartesian waypoint motion.
Definition cartesian_waypoint_motion.hpp:24
std::tuple< Vector7d, Vector7d, Vector7d > getAbsoluteInputLimits() const override
Definition cartesian_waypoint_motion.cpp:125
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
Definition cartesian_waypoint_motion.cpp:41
void initWaypointMotion(const RobotState &robot_state, const std::optional< franka::CartesianPose > &previous_command, ruckig::InputParameter< 7 > &input_parameter) override
Definition cartesian_waypoint_motion.cpp:18
void setNewWaypoint(const RobotState &robot_state, const std::optional< franka::CartesianPose > &previous_command, const PositionWaypoint< CartesianState > &new_waypoint, ruckig::InputParameter< 7 > &input_parameter) override
Definition cartesian_waypoint_motion.cpp:53
std::tuple< Vector7d, Vector7d, Vector7d > getDesiredState(const RobotState &robot_state) const override
Definition cartesian_waypoint_motion.cpp:137
A motion following multiple positional waypoints in a time-optimal way. Works with arbitrary initial ...
Definition position_waypoint_motion.hpp:33
Relative dynamics factors.
Definition relative_dynamics_factor.hpp:13
Definition dynamics_limit.cpp:8
Eigen::Vector< double, 7 > Vector7d
Definition types.hpp:11
Eigen::Affine3d Affine
Definition types.hpp:15
A position waypoint with a target and optional parameters.
Definition position_waypoint_motion.hpp:20
Full state of the robot.
Definition robot_state.hpp:23