robots_ros2
ROS 2 robot interface implementations.
This module defines ROS 2-backed robot wrappers used by RobotBlockSet robot interfaces. It provides communication plumbing, controller integration, state feedback handling, and motion-execution helpers for multiple robot platforms.
- class robotblockset.ros2.robots_ros2.robot_ros2(name: str, namespace: str = '', joint_states_topic: str | None = 'joint_states', control_strategy: str | None = None, strategy_to_controller_interface_mapping: Dict[str, RosControllerInterface] | None = None, node: rclpy.node.Node | None = None, control_manager_name: str | None = 'controller_manager')[source]
Bases:
robotBase class for ROS 2-backed robot interfaces.
- Attributes:
Name (str) – Name of the ROS 2 node and RobotBlockSet robot instance.
_namespace (str) – Normalized ROS namespace prefix used for topics, actions, and services.
controller (RosControllerInterface | None) – Active controller interface bound to the robot.
joint_state (JointState | None) – Last received joint-state message.
force_state (WrenchStamped | None) – Last received force/torque message.
Initialize a ROS 2 robot interface.
- Parameters:
name (str) – Name of the robot node.
namespace (str, optional) – Namespace for the robot topics, actions, and services.
joint_states_topic (str | None, optional) – Relative topic used to subscribe to joint states. If
None, no joint-state subscription is created.control_strategy (str | None, optional) – Initial RobotBlockSet control strategy.
strategy_to_controller_interface_mapping (dict[str, RosControllerInterface] | None, optional) – Mapping from strategy names to controller interface instances.
node (Node | None, optional) – Optional externally created ROS 2 node to use. If
None, a new node is created with the given name.control_manager_name (str, optional) – Name of the ROS 2 controller manager.
Notes
Subclasses may create additional subscriptions, clients, and publishers before calling
_start_spinning().- __init__(name: str, namespace: str = '', joint_states_topic: str | None = 'joint_states', control_strategy: str | None = None, strategy_to_controller_interface_mapping: Dict[str, RosControllerInterface] | None = None, node: rclpy.node.Node | None = None, control_manager_name: str | None = 'controller_manager') None[source]
Initialize a ROS 2 robot interface.
- Parameters:
name (str) – Name of the robot node.
namespace (str, optional) – Namespace for the robot topics, actions, and services.
joint_states_topic (str | None, optional) – Relative topic used to subscribe to joint states. If
None, no joint-state subscription is created.control_strategy (str | None, optional) – Initial RobotBlockSet control strategy.
strategy_to_controller_interface_mapping (dict[str, RosControllerInterface] | None, optional) – Mapping from strategy names to controller interface instances.
node (Node | None, optional) – Optional externally created ROS 2 node to use. If
None, a new node is created with the given name.control_manager_name (str, optional) – Name of the ROS 2 controller manager.
Notes
Subclasses may create additional subscriptions, clients, and publishers before calling
_start_spinning().
- GetState() None[source]
Update the RobotBlockSet state from the latest ROS 2 messages.
Notes
Joint state, force/torque data, and controller reference state are copied into the RobotBlockSet
_actualand_commandcontainers.
- AvailableStrategies() List[str][source]
Return the available control strategies for the robot.
- Returns:
A list of available control strategies.
- Return type:
List[str]
- SetStrategy(new_strategy: str) None[source]
Switch the active control strategy.
- Parameters:
new_strategy (str) – Name of the control strategy to activate.
- Return type:
None
Notes
The current controller is stopped and unregistered before the new ROS 2 controller is loaded, switched, and activated.
- Raises:
ValueError – If the specified strategy is not supported.
- isConnected() bool[source]
Check whether the robot has received initial state feedback.
- Returns:
Trueif the robot is connected, otherwiseFalse.- Return type:
bool
- Shutdown(join_timeout: float = 2.0) None[source]
Shut down the robot node and its background executor.
- Parameters:
join_timeout (float, optional) – Seconds to wait for the background spin thread to stop.
- StopMotion() int | None[source]
Stop the current motion and reset the local target state.
- Returns:
Result code from the controller’s abort call, if available.
- Return type:
int | None
Notes
The robot state is switched to stop mode and the current RobotBlockSet target is reset even when the controller does not provide an explicit abort method.
- EnableWaitForActionServer(check: bool = True) None[source]
Enable waiting for action completion callbacks.
- Parameters:
check (bool, optional) – Whether to enable check. Default is True.
- Return type:
None
- WaitUntilDone(timeout: float | None = None) int[source]
Wait until the controller reports motion completion.
- Parameters:
timeout (float, optional) – Maximum time to wait in seconds. If
None, wait indefinitely.- Returns:
Motion result code reported by the controller.
- Return type:
int
Notes
This method polls
self.controller.motion_doneand updates the robot state while waiting. It is a blocking helper and should not be used from real-time or callback threads.
- GoTo_q(q: ndarray, qdot: ndarray | None = None, trq: ndarray | None = None, wait: float | None = None, **kwargs: Any) int[source]
Command the robot to move to a joint configuration.
- Parameters:
q (JointConfigurationType) – Desired joint positions (nj,).
qdot (JointVelocityType, optional) – Desired joint velocities (nj,).
trq (JointTorqueType, optional) – Desired joint torques (nj,).
wait (float, optional) – Time step used for synchronization and command execution. If
None,self.tsampis used.
- Returns:
Motion result code.
- Return type:
int
Notes
If the active controller does not implement direct joint commands, the method falls back to a two-point joint trajectory.
- Raises:
ValueError – If control is not implemented in controller.
- GoTo_qtraj(q: ndarray, qdot: ndarray, qddot: ndarray, time: ndarray) int[source]
Command the robot to follow a joint trajectory.
- Parameters:
q (JointPathType) – Desired joint positions for the trajectory (n, nj), where n is the number of trajectory points.
qdot (JointPathType) – Desired joint velocities for the trajectory (n, nj), where n is the number of trajectory points.
qddot (JointPathType) – Desired joint accelerations for the trajectory (n, nj). Not used in ROS2 controller.
time (TimesType) – Time points for the trajectory (n,).
- Returns:
Controller status code (0 for success).
- Return type:
int
Notes
On success, the final trajectory point is copied into the RobotBlockSet command state.
- Raises:
ValueError – If control is not implemented in controller.
- GoTo_X(x: ndarray, xdot: ndarray, trq: ndarray, wait: float, **kwargs: Any) int[source]
Command the robot in Cartesian space.
- Parameters:
x (Pose3DType) – Desired end-effector pose.
xdot (Velocity3DType) – Desired end-effector twist.
trq (WrenchType) – Desired end-effector wrench.
wait (float) – Time step used for controller synchronization.
**kwargs (Any) – Additional controller-specific keyword arguments.
- Returns:
Motion result code.
- Return type:
int
Notes
Successful commands update the RobotBlockSet Cartesian command state.
- Raises:
ValueError – If control is not implemented in controller.
- GetCartesianCompliance() Any[source]
Return Cartesian compliance parameters from the active controller.
- SetCartesianCompliance(Kp: Any | None = None, Kr: Any | None = None, R: Any | None = None, D: float | None = None, hold_pose: bool = True) int[source]
Update Cartesian compliance through the active controller.
- GetCartesianStiffness() Any[source]
Return Cartesian stiffness parameters from the active controller.
- SetCartesianStiffness(Kp: Any | None = None, Kr: Any | None = None, hold_pose: bool = True) int[source]
Update Cartesian stiffness through the active controller.
- SetCartesianDamping(D: float | None = None, hold_pose: bool = True) int[source]
Update Cartesian damping through the active controller.
- SetCartesianSoft(stiffness: Any, hold_pose: bool = True) int[source]
Scale Cartesian compliance through the active controller.
- SetCartesianStiff(hold_pose: bool = True) int[source]
Set Cartesian stiffness to the active controller’s stiff defaults.
Classes
|
Base class for ROS 2-backed robot interfaces. |