MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
cartesian_planning Namespace Reference

Classes

struct  CollisionCheckOptions
 Contains options for path collision checking. More...
 
struct  ErrorType
 
struct  PathCollisionInfo
 Struct to hold information about path collisions. More...
 
struct  PathIKOptions
 

Typedefs

using JointSpacePath = std::vector< Eigen::VectorXd >
 
using Path = std::vector< Eigen::Isometry3d >
 

Enumerations

enum class  TipConstraint { kPositionOnly , kPositionAndOrientation }
 Possible task-space constraints when solving kinematics for a path. More...
 

Functions

template<int Rows = Eigen::Dynamic, int Cols = Eigen::Dynamic>
Eigen::Matrix< double, Cols, Rows > dampedLeastSquaresInverse (const Eigen::Matrix< double, Rows, Cols > &matrix, double damping)
 Compute the Damped Least Squares inverse of a matrix.
 
tl::expected< Path, ErrorTypeinterpolate (const Eigen::Isometry3d &start, const Eigen::Isometry3d &end, double max_translational_step, double max_angular_step)
 Interpolate a Cartesian segment at a given density.
 
tl::expected< Path, ErrorTypeinterpolate (const std::vector< Eigen::Isometry3d > &path, double max_translational_step, double max_angular_step, double blending_radius)
 Interpolate a Cartesian path at a given density.
 
tl::expected< Eigen::Matrix6Xd, std::string > computeJacobianForChain (const moveit::core::RobotState &state, const moveit::core::JointModelGroup &group, const moveit::core::LinkModel &tip_link, const Eigen::Vector3d &tip_offset)
 Compute the Jacobian matrix for a given tip link in a kinematic chain.
 
tl::expected< Eigen::MatrixXd, std::string > computeMultiTipJacobian (const moveit::core::RobotState &state, const moveit::core::JointModelGroup &group, const std::vector< const moveit::core::LinkModel * > &tip_links, const std::vector< Eigen::Vector3d > &tip_offsets)
 Compute the Jacobian matrix for a kinematic tree with multiple tips.
 
Eigen::Vector3d rotationToAxisAngleVector (const Eigen::Quaterniond &rotation)
 Converts a 3D rotation given by a quaternion into its axis-angle (u-theta) representation.
 
Eigen::Vector6d poseToPoseVector (const Eigen::Isometry3d &pose)
 Converts a 3D Pose into its 6D vector representation (t, u-theta).
 
Eigen::Vector6d poseError (const Eigen::Isometry3d &a, const Eigen::Isometry3d &b)
 Computes the 3D error (translation and orientation) between two poses.
 
template<class LinearPart >
Eigen::Matrix6d twistRotationMatrix (const LinearPart &rotation)
 Computes the 6x6 twist rotation matrix corresponding to a rotation.
 
Eigen::Vector6d transformTwist (const Eigen::Vector6d &twist_a, const Eigen::Isometry3d &b_pose_a)
 Transforms a twist in frame a to frame b, including the omega.cross(r) term.
 
Eigen::VectorXd jointLimitAvoidanceTask (const Eigen::VectorXd &lower_limits, const Eigen::VectorXd &upper_limits, const Eigen::VectorXd &joint_values, double activation_fraction, double gain)
 A nullspace task to stay away from joint limits.
 
tl::expected< JointSpacePath, ErrorTypepathIK (moveit::core::RobotState &robot_state, const moveit::core::JointModelGroup &group, const std::vector< const moveit::core::LinkModel * > &tip_links, const Path &reference_path, const PathIKOptions &options)
 Computes the incremental Inverse Kinematics over a given Cartesian path, for multiple tips.
 
tl::expected< JointSpacePath, ErrorTypepathIK (moveit::core::RobotState &robot_state, const moveit::core::JointModelGroup &group, const moveit::core::LinkModel &tip_link, const Path &reference_path, const PathIKOptions &options)
 Computes the incremental Inverse Kinematics over a given Cartesian path, for a single tip.
 
tl::expected< std::vector< Eigen::VectorXd >, std::string > downsamplePath (const moveit::core::JointModelGroup &group, const JointSpacePath &path, const moveit::core::RobotState &reference_robot_state, double joint_space_step, double cartesian_space_step, std::vector< std::size_t > *mapping=nullptr)
 Downsamples a given path to a given resolution.
 
bool isPathInCollision (const moveit::core::JointModelGroup &group, const JointSpacePath &path, const CollisionCheckOptions &options, planning_scene::PlanningScene &planning_scene, PathCollisionInfo &collision_info)
 Checks if a given path is in collision.
 
tl::expected< trajectory_processing::Trajectory, std::string > createTrajectoryFromWaypoints (const std::vector< Eigen::VectorXd > &waypoints, const Eigen::VectorXd &max_joint_velocities, const Eigen::VectorXd &max_joint_accelerations, const double velocity_scale_factor, const double acceleration_scale_factor)
 Create a trajectory from a list of waypoints using the trajectory_processing library.
 
tl::expected< trajectory_msgs::msg::JointTrajectory, std::string > createTrajectoryFromWaypoints (const moveit::core::JointModelGroup &group, const std::vector< Eigen::VectorXd > &waypoints, const double velocity_scale_factor, const double acceleration_scale_factor, const int sampling_rate)
 Create a trajectory message from a list of waypoints.
 
tl::unexpected< ErrorTypeerrorWithMessage (const std::string &error_message)
 
template<typename Scalar , int Rows, int Cols, int Options, int MaxRows, int MaxCols>
Eigen::Matrix< Scalar, Cols, 1, Options, MaxCols, 1 > velocityInverseKinematics (const Eigen::MatrixBase< Eigen::Matrix< Scalar, Rows, Cols, Options, MaxRows, MaxCols > > &jacobian, double damping, const Eigen::Matrix< Scalar, Rows, 1, Options, MaxRows, 1 > &cartesian_velocity, const Eigen::MatrixBase< Eigen::Matrix< Scalar, Cols, 1, Options, MaxCols, 1 > > &nullspace_component)
 Compute joint velocities corresponding to a given Cartesian velocity.
 
tl::expected< Eigen::MatrixXd, std::string > computeMultiTipJacobian (const moveit::core::RobotState &state, const moveit::core::JointModelGroup &group, const std::vector< const LinkModel * > &tip_links, const std::vector< Eigen::Vector3d > &tip_offsets)
 

Variables

constexpr double kDefaultPathIkTranslationalStep = 0.001
 
constexpr double kDefaultPathIkAngularStep = 0.001
 
constexpr double kMaxAllowedPathDeviationTranslation = 0.001
 
constexpr double kMaxAllowedPathDeviationRotation = 0.001
 
constexpr double kJacobianInverseDamping = 0.001
 
constexpr double kDistanceToJointLimitThreshold = 0.001
 

Typedef Documentation

◆ JointSpacePath

using cartesian_planning::JointSpacePath = typedef std::vector<Eigen::VectorXd>

◆ Path

using cartesian_planning::Path = typedef std::vector<Eigen::Isometry3d>

Enumeration Type Documentation

◆ TipConstraint

Possible task-space constraints when solving kinematics for a path.

A constraint needs to be always satisfied by the solution at every waypoint.

Enumerator
kPositionOnly 
kPositionAndOrientation 

Function Documentation

◆ computeJacobianForChain()

tl::expected< Eigen::Matrix6Xd, std::string > cartesian_planning::computeJacobianForChain ( const moveit::core::RobotState &  state,
const moveit::core::JointModelGroup &  group,
const moveit::core::LinkModel &  tip_link,
const Eigen::Vector3d &  tip_offset 
)

Compute the Jacobian matrix for a given tip link in a kinematic chain.

This function computes the Jacobian matrix for a kinematic chain. The Jacobian matrix is computed for given tip link and an optional position offset. The Jacobian matrix is computed in the frame of the root link of the kinematic chain. The columns in the Jacobian are ordered by the joints in the joint model group. It will contain as many columns as active joints in the joint model group. The number of rows will always be 6 (translation / axis-angle rotation). Therefore, the Jacobian will be a 6 x M matrix, where M the number of active joints. The Cartesian velocity at the tips can then be computed as:

v = J * q_dot

Parameters
stateThe current robot state, needs to be up to date (not dirty), or the function will return error.
groupThe joint model group for which to compute the Jacobian. It needs to be a kinematic chain, or the function will return an error.
tip_linkThe link for which to compute the Jacobian. Must be part of the group or a descendant link.
tip_offsetTranslational offset from the tip link to the point for which the Jacobian is computed. The offsets are expressed in the frame of the tip link.
Returns
the Jacobian matrix if successful, or an error message if the computation failed.

◆ computeMultiTipJacobian() [1/2]

tl::expected< Eigen::MatrixXd, std::string > cartesian_planning::computeMultiTipJacobian ( const moveit::core::RobotState &  state,
const moveit::core::JointModelGroup &  group,
const std::vector< const LinkModel * > &  tip_links,
const std::vector< Eigen::Vector3d > &  tip_offsets 
)

◆ computeMultiTipJacobian() [2/2]

tl::expected< Eigen::MatrixXd, std::string > cartesian_planning::computeMultiTipJacobian ( const moveit::core::RobotState &  state,
const moveit::core::JointModelGroup &  group,
const std::vector< const moveit::core::LinkModel * > &  tip_links,
const std::vector< Eigen::Vector3d > &  tip_offsets 
)

Compute the Jacobian matrix for a kinematic tree with multiple tips.

This function computes the Jacobian matrix for a kinematic tree with multiple tips. The Jacobian matrix is computed for the tips and the given offsets. The Jacobian matrix is computed in the frame of the root link of the kinematic tree. The columns in the Jacobian are ordered by the joints in the joint model group. It will contain as many columns as active joints in the joint model group. The number of rows will depend on the number of tips (each tip will add 6 rows to the Jacobian). Therefore, the multi-tip Jacobian will be a 6N x M matrix, where N is the number of tips and M the number of active joints. Cartesian velocities for the tips can then be computed as: [v1; v2; ...; vN] = J * q_dot

Parameters
stateThe current robot state, needs to be up to date (not dirty), or the function will return error.
groupThe joint model group for which to compute the Jacobian. It needs to be a kinematic tree, i.e. all joints are connected to a single root joint.
tip_linksThe links for which to compute the Jacobian. The links must be part of the joint group.
tip_offsetsTranslational offsets from the tip links to the point for which the Jacobian is computed. The offsets are expressed in the frame of the tip links.
Returns
the Jacobian matrix if successful, or an error message if the computation failed.

◆ createTrajectoryFromWaypoints() [1/2]

tl::expected< trajectory_msgs::msg::JointTrajectory, std::string > cartesian_planning::createTrajectoryFromWaypoints ( const moveit::core::JointModelGroup &  group,
const std::vector< Eigen::VectorXd > &  waypoints,
const double  velocity_scale_factor,
const double  acceleration_scale_factor,
const int  sampling_rate 
)

Create a trajectory message from a list of waypoints.

Maximum joint velocities / accelerations are obtained from the given joint model group.

Parameters
groupThe joint model group to use for the trajectory.
waypointsList of waypoints to create a trajectory from.
velocity_scale_factorScale factor for the maximum joint velocities.
acceleration_scale_factorScale factor for the maximum joint accelerations.
sampling_rateThe sampling rate to use for the trajectory.
Returns
A JointTrajectory message if successful, or an error message if the trajectory could not be created.

◆ createTrajectoryFromWaypoints() [2/2]

tl::expected< trajectory_processing::Trajectory, std::string > cartesian_planning::createTrajectoryFromWaypoints ( const std::vector< Eigen::VectorXd > &  waypoints,
const Eigen::VectorXd &  max_joint_velocities,
const Eigen::VectorXd &  max_joint_accelerations,
const double  velocity_scale_factor,
const double  acceleration_scale_factor 
)

Create a trajectory from a list of waypoints using the trajectory_processing library.

Parameters
waypointsList of waypoints to create a trajectory from.
max_joint_velocitiesMaximum joint velocities for the robot.
max_joint_accelerationsMaximum joint accelerations for the robot.
velocity_scale_factorScale factor for the maximum joint velocities.
acceleration_scale_factorScale factor for the maximum joint accelerations.
Returns
A timed trajectory if successful, or an error message if the trajectory could not be created.

◆ dampedLeastSquaresInverse()

template<int Rows = Eigen::Dynamic, int Cols = Eigen::Dynamic>
Eigen::Matrix< double, Cols, Rows > cartesian_planning::dampedLeastSquaresInverse ( const Eigen::Matrix< double, Rows, Cols > &  matrix,
double  damping 
)

Compute the Damped Least Squares inverse of a matrix.

This function is templated on the number of rows and columns, which allows using static Eigen types if desired. 'damping' must be positive or zero. A very small value may cause instabilities around singularities. A larger value will behave better at singularities at the cost of deviations and longer convergence times. A value around 0.01 is normally good enough for servoing/control applications. Planning applications (e.g. IK, etc.) may use lower values for faster convergence. For reference see: http://graphics.cs.cmu.edu/nsp/course/15464-s17/lectures/iksurvey.pdf

◆ downsamplePath()

tl::expected< std::vector< Eigen::VectorXd >, std::string > cartesian_planning::downsamplePath ( const moveit::core::JointModelGroup &  group,
const JointSpacePath path,
const moveit::core::RobotState &  reference_robot_state,
double  joint_space_step,
double  cartesian_space_step,
std::vector< std::size_t > *  mapping = nullptr 
)

Downsamples a given path to a given resolution.

Given a dense path, this function removes waypoints so that any two adjacent waypoints are not closer than joint_space_step in joint-space (L1 norm) or cartesian_space_step in Cartesian space (Euclidean distance on the translation at the last link of the group). This can be helpful to downsample a dense path (e.g. from a trajectory) but keeping a desired 'resolution' both in joint-space and Cartesian space, for instance for a dense-enough collision check.

The first and last waypoints of the path are always included in the output. All other waypoints in the output were also part of the original path, i.e. this function doesn't create new waypoints, just removes some, and keeps others. If the waypoints in the input are already separated more than joint_space_step and cartesian_space_step, the path won't be modified.

reference_robot_state is a RobotState to be used as reference when computing forward kinematics.

If a mapping argument is provided, it will be filled in with the mapping between the new path indexes and the previous path indexes, i.e. mapping[i] will contain the original path index that corresponds to index i in the new path.

Returns
A downsampled version of the path, where adjacent waypoints are spaced not closer than joint_space_step or cartesian_space_step.

◆ errorWithMessage()

tl::unexpected< ErrorType > cartesian_planning::errorWithMessage ( const std::string &  error_message)
inline

◆ interpolate() [1/2]

tl::expected< Path, ErrorType > cartesian_planning::interpolate ( const Eigen::Isometry3d &  start,
const Eigen::Isometry3d &  end,
double  max_translational_step,
double  max_angular_step 
)

Interpolate a Cartesian segment at a given density.

This function will interpolate in Cartesian space between the given 'start' and 'end' poses in such a way that adjacent waypoints will always be closer than 'max_translational_step' in 3D translation (meters) and 'max_angular_step' in 3D rotation (radians). 'max_translational_step' and 'max_angular_step' must always be non-zero and positive. Otherwise an error will be returned.

Returns
The interpolated path as a sequence of poses, or an error.

◆ interpolate() [2/2]

tl::expected< Path, ErrorType > cartesian_planning::interpolate ( const std::vector< Eigen::Isometry3d > &  path,
double  max_translational_step,
double  max_angular_step,
double  blending_radius 
)

Interpolate a Cartesian path at a given density.

This function will interpolate in Cartesian space along the given waypoints in such a way that:

  • Adjacent waypoints will always be closer than 'max_translational_step' in 3D translation (meters) and 'max_angular_step' in 3D rotation (radians) for the linear segments of the output path (not necessarily at the corners).
  • Every intermediate waypoint will be 'blended' according to the given 'blending_radius' in order to generate a smooth curve that can be executed continuously by the robot.
  • The initial and final waypoints of the path will be reached exactly.

'max_translational_step', 'max_angular_step' and 'blending_radius' must always be non-zero and positive. 'blending_radius' must also be smaller than half the distance between the closest two waypoints in the input path, i.e. it must be possible to apply the given 'blending_radius'. Otherwise an error will be returned.

Returns
The interpolated path as a sequence of poses, or an error.

◆ isPathInCollision()

bool cartesian_planning::isPathInCollision ( const moveit::core::JointModelGroup &  group,
const JointSpacePath path,
const CollisionCheckOptions options,
planning_scene::PlanningScene &  planning_scene,
PathCollisionInfo collision_info 
)

Checks if a given path is in collision.

Given a joint-space path, this function checks if any waypoint in that path is in collision with the given planning_scene. This function does discrete collision-checking at every waypoint, i.e. it doesn't perform a swept-volume check between two adjacent waypoints.

Collision checking is done according to the options specified in the options parameter.

This function asserts that the path has at least two waypoints.

Returns
true if the path is in collision at any waypoint along the path, and fills in collision_info with information about the collision (e.g. path index where the collision was found).

◆ jointLimitAvoidanceTask()

Eigen::VectorXd cartesian_planning::jointLimitAvoidanceTask ( const Eigen::VectorXd &  lower_limits,
const Eigen::VectorXd &  upper_limits,
const Eigen::VectorXd &  joint_values,
double  activation_fraction,
double  gain 
)

A nullspace task to stay away from joint limits.

This function computes the gradient of a distance-to-joint-limits cost function. The cost function is defined as follows:

  • Given the lower limits (ll) and the upper limits (ul).
  • Given an activation distance (ad), defined as a distance to the joint limits.
  • We compute the lower and upper activation thresholds (lt and ut), as: lt = ll + ad ut - ul - ad
  • Given the current joint values (q), and a cost gain 'k', the cost is defined as: 0 if lt <= q <= ut k * (q - ut)^2 if q > ut k * (q - lt)^2 if q < lt

The cost is zero if the joint values are further than the activation distance from the limits. If the joint values become closer than the activation distance to a limit, the cost increases quadratically with the encroachment on the activation threshold. The gain 'k' determines how quickly the cost increases.

The gradient of this cost function is given by: 0 if lt <= q <= ut k * (q - ut) if q > ut k * (ut - q) if q < lt

lower_limits and upper_limits are the joints lower and upper position limits. joint_values contains the current joint values. activation_fraction determines the activation thresholds, as a fraction of the joint range, e.g. a value of 0.1 will activate the cost when a joint value is closer to the limit than 10% of the joint range. gain controls how quickly the cost increases with the encroachment into the activation region.

◆ pathIK() [1/2]

tl::expected< JointSpacePath, ErrorType > cartesian_planning::pathIK ( moveit::core::RobotState &  robot_state,
const moveit::core::JointModelGroup &  group,
const moveit::core::LinkModel &  tip_link,
const Path reference_path,
const PathIKOptions options 
)

Computes the incremental Inverse Kinematics over a given Cartesian path, for a single tip.

See the multi-tip version above for details.

Parameters
robot_stateThe current robot state, with the initial joint-space configuration.
groupThe joint model group to solve the kinematics for.
tip_linkThe link to move according to the given reference_path.
reference_pathThe path to follow in Cartesian space.
optionsThe options to use when solving the kinematics.
Returns
A dense joint-space path to move the robot along the reference path, or an error if the kinematics couldn't be solved. In that case, ErrorType may contain the section of the path that could be solved, if a solvable section was found.

◆ pathIK() [2/2]

tl::expected< JointSpacePath, ErrorType > cartesian_planning::pathIK ( moveit::core::RobotState &  robot_state,
const moveit::core::JointModelGroup &  group,
const std::vector< const moveit::core::LinkModel * > &  tip_links,
const Path reference_path,
const PathIKOptions options 
)

Computes the incremental Inverse Kinematics over a given Cartesian path, for multiple tips.

The initial joint-space configuration and starting pose are given by 'robot_state', which needs to be set accordingly before this call. 'reference_path' is the path to follow in Cartesian space. It should be given with respect to the group root link. This function will densely sample the space along the reference path, and compute the multi-tip incremental inverse kinematics. The intermediate waypoints will be 'blended' with the given radius (in 'options') in order to create a smooth dense path. The solution is guaranteed to not contain large joint-space reconfigurations. The output of the function is still a path, it won't contain any timing information. Before its execution, the joint-space path will need to be timed via a trajectory timing algorithm.

The reference_path doesn't need to start at any of the given tip links. It can be anywhere in the space, but the given tip_links will move relative to the given reference path, based on their relative pose to the reference path in the given initial robot_state.

Parameters
robot_stateThe current robot state, with the initial joint-space configuration. The current robot state is used to determine the initial pose of the tips to be controller with respect to the given reference_path.
groupThe joint model group to solve the kinematics for. It can be a chain or a tree if solving for multiple tips.
tip_linksThe links to move according to the given reference_path. The links must be part of the joint group.
reference_pathThe path to follow in Cartesian space. It should be given with respect to the group root link.
optionsThe options to use when solving the kinematics. See PathIKOptions for more information.
Returns
A dense joint-space path to move the robot along the reference path, or an error if the kinematics couldn't be solved. In that case, ErrorType may contain the section of the path that could be solved, if a solvable section was found.

◆ poseError()

Eigen::Vector6d cartesian_planning::poseError ( const Eigen::Isometry3d &  a,
const Eigen::Isometry3d &  b 
)

Computes the 3D error (translation and orientation) between two poses.

The error is given as a 6D vector (t u-theta), with the first 3 components containing the translation error, and the last three components containing the orientation error in an axis-angle representation.

Returns
a 6D vector with the translation and orientation error (t u-theta).

◆ poseToPoseVector()

Eigen::Vector6d cartesian_planning::poseToPoseVector ( const Eigen::Isometry3d &  pose)

Converts a 3D Pose into its 6D vector representation (t, u-theta).

Returns
a 6D vector where the translation part is directly the translation part of the input pose, and the rotation part is the axis-angle representation of the rotation.

◆ rotationToAxisAngleVector()

Eigen::Vector3d cartesian_planning::rotationToAxisAngleVector ( const Eigen::Quaterniond &  rotation)

Converts a 3D rotation given by a quaternion into its axis-angle (u-theta) representation.

Returns
a 3D vector with the axis-angle representation of the given quaternion.

◆ transformTwist()

Eigen::Vector6d cartesian_planning::transformTwist ( const Eigen::Vector6d &  twist_a,
const Eigen::Isometry3d &  b_pose_a 
)

Transforms a twist in frame a to frame b, including the omega.cross(r) term.

Parameters
twist_aThe twist in frame a to transform.
b_pose_aThe transform from frame b to frame a.
Returns
The twist in frame b.

◆ twistRotationMatrix()

template<class LinearPart >
Eigen::Matrix6d cartesian_planning::twistRotationMatrix ( const LinearPart &  rotation)

Computes the 6x6 twist rotation matrix corresponding to a rotation.

Parameters
rotationThe 3x3 rotation matrix.
Returns
a 6x6 matrix that rotates a twist by the given rotation.

◆ velocityInverseKinematics()

template<typename Scalar , int Rows, int Cols, int Options, int MaxRows, int MaxCols>
Eigen::Matrix< Scalar, Cols, 1, Options, MaxCols, 1 > cartesian_planning::velocityInverseKinematics ( const Eigen::MatrixBase< Eigen::Matrix< Scalar, Rows, Cols, Options, MaxRows, MaxCols > > &  jacobian,
double  damping,
const Eigen::Matrix< Scalar, Rows, 1, Options, MaxRows, 1 > &  cartesian_velocity,
const Eigen::MatrixBase< Eigen::Matrix< Scalar, Cols, 1, Options, MaxCols, 1 > > &  nullspace_component 
)

Compute joint velocities corresponding to a given Cartesian velocity.

Given a cartesian_velocity, compute and return the corresponding joint velocities. Use nullspace_component to include joint-space costs to the minimization. nullspace_component can be seen as joint-space velocities that will be achieved in a best-effort way, i.e. only if it's kinematically possible. This function is templated on the Eigen matrix template parameters, which allows using static Eigen types if desired, and ensures the input types are compatible. The function is similar to cartesian_planning::dampedLeastSquaresInverse() but it solves for the Cartesian velocity instead of the full Jacobian, which should be faster. See that function for more details.

Variable Documentation

◆ kDefaultPathIkAngularStep

constexpr double cartesian_planning::kDefaultPathIkAngularStep = 0.001
constexpr

◆ kDefaultPathIkTranslationalStep

constexpr double cartesian_planning::kDefaultPathIkTranslationalStep = 0.001
constexpr

◆ kDistanceToJointLimitThreshold

constexpr double cartesian_planning::kDistanceToJointLimitThreshold = 0.001
constexpr

◆ kJacobianInverseDamping

constexpr double cartesian_planning::kJacobianInverseDamping = 0.001
constexpr

◆ kMaxAllowedPathDeviationRotation

constexpr double cartesian_planning::kMaxAllowedPathDeviationRotation = 0.001
constexpr

◆ kMaxAllowedPathDeviationTranslation

constexpr double cartesian_planning::kMaxAllowedPathDeviationTranslation = 0.001
constexpr