CartesianCommandBuilder#

rb::CartesianCommandBuilder expresses a Cartesian tracking request. It can hold one or more task-space targets plus optional joint-position targets and stop thresholds for tracking error.

Header

Header

#include <rby1-sdk/robot_command_builder.h>

Declaration

Namespace

rb

Kind

class

Primary role

Hold Cartesian targets and stop conditions for tracking tasks.

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.

SetMinimumTime(...)

Set the requested minimum execution time.

Useful for time-scaled motion.

SetStop*TrackingError(...)

Set thresholds that abort on excessive tracking error.

Covers position, orientation, and joint-position errors.

Key Numeric Parameters

Method

Unit / encoding

Notes

SetMinimumTime(minimum_time)

s

Minimum execution time for the Cartesian motion.

AddTarget(..., T, linear_velocity_limit, angular_velocity_limit, acceleration_limit_scaling)

SE(3), m/s, rad/s, Dimensionless

T carries translation in meters. acceleration_limit_scaling is a normalized scaling factor with documented range (0, 1].

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

rad, rad/s, rad/s^2

Auxiliary joint-space posture bias and optional per-joint limits.

SetStopPositionTrackingError(value)

m

Stop threshold on translational tracking error.

SetStopOrientationTrackingError(value)

rad

Stop threshold on rotational tracking error.

SetStopJointPositionTrackingError(value)

rad

Stop threshold on per-joint position tracking error.

Detailed Reference

class CartesianCommandBuilder#

Public Functions

CartesianCommandBuilder()#
~CartesianCommandBuilder()#
CartesianCommandBuilder &AddJointPositionTarget(const std::string &joint_name, double target_position, std::optional<double> velocity_limit = std::nullopt, std::optional<double> acceleration_limit = std::nullopt)#
CartesianCommandBuilder &AddTarget(const std::string &ref_link_name, const std::string &link_name, const math::SE3::MatrixType &T, double linear_velocity_limit, double angular_velocity_limit, double acceleration_limit_scaling = 1.)#
CartesianCommandBuilder &SetCommandHeader(const CommandHeaderBuilder &builder)#
CartesianCommandBuilder &SetMinimumTime(double minium_time)#
CartesianCommandBuilder &SetStopJointPositionTrackingError(double stop_joint_position_tracking_error)#
CartesianCommandBuilder &SetStopOrientationTrackingError(double stop_orientation_tracking_error)#
CartesianCommandBuilder &SetStopPositionTrackingError(double stop_position_tracking_error)#

Related Types

Examples

  • demo_motion.cpp

  • kinematic_calibration2.cpp