CartesianImpedanceControlCommandBuilder#

rb::CartesianImpedanceControlCommandBuilder is the most feature-rich task-space compliance primitive. It extends the Cartesian command path with joint limits, joint stiffness, nullspace targets, and reset behavior.

Header

Header

#include <rby1-sdk/robot_command_builder.h>

Declaration

Namespace

rb

Kind

class

Primary role

Hold a Cartesian impedance request with richer task and nullspace data.

Public Member Functions

Method

Purpose

Notes

SetCommandHeader(...)

Attach shared header metadata.

Uses CommandHeaderBuilder.

AddTarget(...) and AddJointPositionTarget(...)

Add task-space and optional joint-space targets.

AddTarget(...) is the main task-space API.

AddJointLimit(...), SetJointStiffness(...), SetJointDampingRatio(...), SetJointTorqueLimit(...)

Configure nullspace and impedance terms.

These are the main additions over CartesianCommandBuilder.

SetNullspaceJointTarget(...) and SetResetReference(...)

Control nullspace bias and reference reset behavior.

Useful in long-running Cartesian tasks.

SetMinimumTime(...) and SetStop*TrackingError(...)

Set time and stop thresholds.

Covers position, orientation, and joint-position errors.

Key Numeric Parameters

Method

Unit / encoding

Notes

SetMinimumTime(minimum_time)

s

Minimum execution time.

AddTarget(..., T, linear_velocity_limit, angular_velocity_limit, linear_acceleration_limit, angular_acceleration_limit)

SE(3), m/s, rad/s, m/s^2, rad/s^2

T carries translation in meters. Velocity and acceleration limits are internal solver bounds.

AddJointPositionTarget(..., target_position, velocity_limit, acceleration_limit)

rad, rad/s, rad/s^2

Auxiliary joint target used by the optimization stage.

SetNullspaceJointTarget(target_position, weight, k_p, k_d, cost_weight)

rad, Dimensionless, Not specified

target_position is joint-space. weight and cost_weight are optimization weights. Public docs do not assign units to k_p or k_d.

SetStopPositionTrackingError(value)

m

Stop threshold on translational error.

SetStopOrientationTrackingError(value)

rad

Stop threshold on rotational error.

SetStopJointPositionTrackingError(value)

rad

Stop threshold on joint-position error.

SetJointStiffness(stiffness)

Nm/rad

Per-joint stiffness values.

SetJointTorqueLimit(torque_limit)

Nm

Per-joint torque saturation values.

SetJointDampingRatio(damping_ratio)

Dimensionless

Joint damping ratio used to derive the damping matrix.

Detailed Reference

class CartesianImpedanceControlCommandBuilder#

Public Functions

CartesianImpedanceControlCommandBuilder()#
~CartesianImpedanceControlCommandBuilder()#
CartesianImpedanceControlCommandBuilder &AddJointLimit(const std::string &joint_name, double lower, double upper)#
CartesianImpedanceControlCommandBuilder &AddJointPositionTarget(const std::string &joint_name, double target_position, std::optional<double> velocity_limit = std::nullopt, std::optional<double> acceleration_limit = std::nullopt)#
CartesianImpedanceControlCommandBuilder &AddTarget(const std::string &ref_link_name, const std::string &link_name, const math::SE3::MatrixType &T, std::optional<double> linear_velocity_limit = std::nullopt, std::optional<double> angular_velocity_limit = std::nullopt, std::optional<double> linear_acceleration_limit = std::nullopt, std::optional<double> angular_acceleration_limit = std::nullopt)#
CartesianImpedanceControlCommandBuilder &SetCommandHeader(const CommandHeaderBuilder &builder)#
CartesianImpedanceControlCommandBuilder &SetJointDampingRatio(double damping_ratio)#
CartesianImpedanceControlCommandBuilder &SetJointStiffness(const Eigen::VectorXd &stiffness)#
CartesianImpedanceControlCommandBuilder &SetJointTorqueLimit(const Eigen::VectorXd &torque_limit)#
CartesianImpedanceControlCommandBuilder &SetMinimumTime(double minium_time)#
CartesianImpedanceControlCommandBuilder &SetNullspaceJointTarget(const Eigen::VectorXd &target_position, const Eigen::VectorXd &weight, std::optional<double> k_p = std::nullopt, std::optional<double> k_d = std::nullopt, std::optional<double> cost_weight = std::nullopt)#
CartesianImpedanceControlCommandBuilder &SetResetReference(bool reset_reference)#
CartesianImpedanceControlCommandBuilder &SetStopJointPositionTrackingError(double stop_joint_position_tracking_error)#
CartesianImpedanceControlCommandBuilder &SetStopOrientationTrackingError(double stop_orientation_tracking_error)#
CartesianImpedanceControlCommandBuilder &SetStopPositionTrackingError(double stop_position_tracking_error)#

Related Types

Examples

  • gravity_compensation.cpp