OptimalControl

rb::OptimalControl is the runtime solver object behind the SDK’s optimal-control workflow. It is separate from the command builder: this page covers the solver itself and the nested target records it consumes.

Header

Header

#include <rby1-sdk/math/optimal_control.h>

Declaration

Namespace

rb

Kind

class template

Primary role

Solve constrained model-based control problems against a dynamics model.

Member Types / Enums

Type

Purpose

Notes

ExitCode

Solver exit status.

Check after each call to Solve(...).

Input and target structs

Bundle COM, link, joint-angle, and nullspace targets.

These records define the actual optimization problem.

Public Member Functions

Method group

Purpose

Notes

OptimalControl(...)

Construct the solver for one robot model and joint subset.

Binds the solver to a dynamics model.

Solve(...)

Run the optimal-control solve.

Overloads cover bounded and unbounded position-limit cases.

GetExitCode*(), GetError(), GetManipulability()

Inspect the result of the most recent solve.

Use for diagnostics and controller tuning.

Detailed Reference

template<int DOF>
class OptimalControl

Public Types

enum class ExitCode : int

Values:

enumerator kNoError
enumerator kInequalityConstraintViolation
enumerator kQPSolverError

Public Functions

inline explicit OptimalControl(std::shared_ptr<dyn::Robot<DOF>> robot, const std::vector<unsigned int> &joint_idx, bool nullspace_mapping = true, bool soft_position_boundary = false)
inline double GetError() const
inline ExitCode GetExitCode() const
inline std::string GetExitCodeMessage() const
inline double GetManipulability() const
inline std::optional<Eigen::VectorXd> Solve(Input in, std::shared_ptr<dyn::State<DOF>> state, double dt, double error_scaling, const Eigen::Vector<double, DOF> &position_lower_limit, const Eigen::Vector<double, DOF> &position_upper_limit, const Eigen::Vector<double, DOF> &velocity_limit, const Eigen::Vector<double, DOF> &acceleration_limit, bool need_forward_kinematics = false)
inline std::optional<Eigen::VectorXd> Solve(Input in, std::shared_ptr<dyn::State<DOF>> state, double dt, double error_scaling, const Eigen::Vector<double, DOF> &velocity_limit, const Eigen::Vector<double, DOF> &acceleration_limit, bool need_forward_kinematics = false)
struct COMTarget

Public Members

Eigen::Vector3d com = {Eigen::Vector3d::Zero()}
double weight = {0.}
struct Input

Public Members

std::optional<COMTarget> com_target
std::optional<NullspaceJointTarget> nullspace_q_target
std::optional<JointAngleTarget> q_target
struct JointAngleTarget

Public Functions

inline JointAngleTarget()
inline explicit JointAngleTarget(int dof)

Public Members

Eigen::Vector<double, DOF> q
Eigen::Vector<double, DOF> weight
struct LinkTarget

Public Members

math::SE3::MatrixType T = {math::SE3::Identity()}
double weight_orientation = {0.}
double weight_position = {0.}
struct NullspaceJointTarget

Public Functions

inline NullspaceJointTarget()
inline explicit NullspaceJointTarget(int dof)

Public Members

double cost_weight = {1e-3}
double k_d = {0.2}
double k_p = {0.2}
Eigen::Vector<double, DOF> q
Eigen::Vector<double, DOF> weight

Related Types

Examples

  • optimal_control.cpp is the direct example for this page.