3#include <franka/robot_state.h>
7#include <ruckig/ruckig.hpp>
35 const RobotState &robot_state,
const std::optional<franka::JointVelocities> &previous_command,
36 ruckig::InputParameter<7> &input_parameter)
override;
39 const RobotState &robot_state,
const std::optional<franka::JointVelocities> &previous_command,
45 const RobotState &robot_state,
const franka::Duration &time_step,
46 const std::optional<franka::JointVelocities> &previous_command,
47 const ruckig::InputParameter<7> &input_parameter)
override;
Joint velocity waypoint motion.
Definition joint_velocity_waypoint_motion.hpp:19
std::tuple< Vector7d, Vector7d, Vector7d > getDesiredState(const RobotState &robot_state) const override
Definition joint_velocity_waypoint_motion.cpp:51
franka::JointVelocities getControlSignal(const RobotState &robot_state, const franka::Duration &time_step, const std::optional< franka::JointVelocities > &previous_command, const ruckig::InputParameter< 7 > &input_parameter) override
Definition joint_velocity_waypoint_motion.cpp:31
std::tuple< Vector7d, Vector7d, Vector7d > getAbsoluteInputLimits() const override
Definition joint_velocity_waypoint_motion.cpp:46
void initWaypointMotion(const RobotState &robot_state, const std::optional< franka::JointVelocities > &previous_command, ruckig::InputParameter< 7 > &input_parameter) override
Definition joint_velocity_waypoint_motion.cpp:20
void checkWaypoint(const VelocityWaypoint< Vector7d > &waypoint) const override
Definition joint_velocity_waypoint_motion.cpp:11
void setNewWaypoint(const RobotState &robot_state, const std::optional< franka::JointVelocities > &previous_command, const VelocityWaypoint< Vector7d > &new_waypoint, ruckig::InputParameter< 7 > &input_parameter) override
Definition joint_velocity_waypoint_motion.cpp:37
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:28
Definition dynamics_limit.cpp:8
Full state of the robot.
Definition robot_state.hpp:20
A waypoint with a target and optional parameters.
Definition waypoint_motion.hpp:33