@@ -267,7 +267,8 @@ class Robot
267267 * @brief [Blocking] Get feedback states of the currently executing
268268 * primitive.
269269 * @return Primitive states in the format of a string list.
270- * @throw CommException if there's no response from the robot.
270+ * @throw CommException if there's no response from the robot or the result
271+ * is invalid.
271272 * @throw ExecutionException if error occurred during execution.
272273 * @warning This function blocks until the reply from the robot is received.
273274 */
@@ -314,7 +315,8 @@ class Robot
314315 * @note No need to call this function if the mounted tool on the robot has
315316 * only one TCP, it'll be used by default.
316317 * @note New TCP index will take effect upon control mode switch, or upon
317- * sending a new primitive command.
318+ * sending a new primitive command. However, this function has no effect in
319+ * plan execution mode as TCP index should be defined in the plan itself.
318320 * @warning This function blocks until the request is successfully delivered
319321 * to the robot.
320322 */
@@ -465,11 +467,11 @@ class Robot
465467 * \times 1} \f$ force and \f$ \mathbb{R}^{3 \times 1} \f$ moment: \f$ [f_x,
466468 * f_y, f_z, m_x, m_y, m_z]^T \f$. Unit: \f$ [N]~[Nm] \f$.
467469 * @param[in] maxLinearVel Maximum Cartesian linear velocity when moving to
468- * the target pose. Default maximum linear velocity is used when set to 0.
469- * Unit: \f$ [m/s] \f$.
470+ * the target pose. A safe value is provided as default. Unit: \f$ [m/s]
471+ * \f$.
470472 * @param[in] maxAngularVel Maximum Cartesian angular velocity when moving
471- * to the target pose. Default maximum angular velocity is used when set to
472- * 0. Unit: \f$ [rad/s] \f$.
473+ * to the target pose. A safe value is provided as default. Unit: \f$
474+ * [rad/s] \f$.
473475 * @throw InputException if input is invalid.
474476 * @throw LogicException if robot is not in the correct control mode.
475477 * @throw ExecutionException if error occurred during execution.
@@ -492,7 +494,7 @@ class Robot
492494 */
493495 void sendCartesianMotionForce (const std::vector<double >& pose,
494496 const std::vector<double >& wrench = std::vector<double >(6 ),
495- double maxLinearVel = 0.0 , double maxAngularVel = 0 .0);
497+ double maxLinearVel = 0.5 , double maxAngularVel = 1 .0);
496498
497499 /* *
498500 * @brief [Non-blocking] Set motion stiffness for the Cartesian motion-force
@@ -558,8 +560,9 @@ class Robot
558560 * @throw LogicException if robot is not in the correct control mode.
559561 * @throw ExecutionException if error occurred during execution.
560562 * @note Applicable control modes: RT/NRT_CARTESIAN_MOTION_FORCE.
561- * @warning The robot will automatically reset to its nominal preferred
562- * joint positions upon re-entering the applicable control modes.
563+ * @warning Upon entering the applicable control modes, the robot will
564+ * automatically set its current joint positions as the preferred joint
565+ * positions.
563566 * @par Null-space posture control
564567 * Similar to human arm, a robotic arm with redundant degree(s) of
565568 * freedom (DOF > 6) can change its overall posture without affecting the
@@ -572,8 +575,8 @@ class Robot
572575 void setNullSpacePosture (const std::vector<double >& preferredPositions);
573576
574577 /* *
575- * @brief [Non-blocking] Reset preferred joint positions to the robot's home
576- * posture .
578+ * @brief [Non-blocking] Reset preferred joint positions to the ones
579+ * automatically recorded when entering the applicable control modes .
577580 * @note Applicable control modes: RT/NRT_CARTESIAN_MOTION_FORCE.
578581 */
579582 void resetNullSpacePosture (void );
0 commit comments