robots_ros
ROS robot interface implementations.
This module defines ROS-backed robot wrappers used by RobotBlockSet robot interfaces. It provides strategy-to-controller mapping, controller switching, logger configuration, and joint- and Cartesian-command forwarding.
- class robotblockset.ros.robots_ros.robot_ros(ns: str = '', init_node: bool = True, multi_node: bool = False, control_strategy: str | None = None, strategy_controller_mapping: dict | None = None)[source]
Bases:
robotBase class for ROS-backed robot interfaces.
- Attributes:
_namespace (str) – ROS namespace prefix used by the robot wrapper.
controller_helper (controller_manager_proxy) – Helper object for loading and switching ROS controllers.
controller (Any) – Active RobotBlockSet controller wrapper.
Initialize the generic ROS robot interface.
- Parameters:
ns (str, optional) – ROS namespace of the robot.
init_node (bool, optional) – If
True, initialize a ROS node for the wrapper.multi_node (bool, optional) – If
True, initialize the ROS node in anonymous mode.control_strategy (str, optional) – Initial RobotBlockSet control strategy.
strategy_controller_mapping (dict[str, tuple[str, Type[Any]]] | None, optional) – Mapping from RobotBlockSet strategy names to pairs of ROS controller names and controller wrapper classes.
Notes
The constructor initializes the controller-manager helper and optionally activates the requested control strategy.
- __init__(ns: str = '', init_node: bool = True, multi_node: bool = False, control_strategy: str | None = None, strategy_controller_mapping: dict | None = None) None[source]
Initialize the generic ROS robot interface.
- Parameters:
ns (str, optional) – ROS namespace of the robot.
init_node (bool, optional) – If
True, initialize a ROS node for the wrapper.multi_node (bool, optional) – If
True, initialize the ROS node in anonymous mode.control_strategy (str, optional) – Initial RobotBlockSet control strategy.
strategy_controller_mapping (dict[str, tuple[str, Type[Any]]] | None, optional) – Mapping from RobotBlockSet strategy names to pairs of ROS controller names and controller wrapper classes.
Notes
The constructor initializes the controller-manager helper and optionally activates the requested control strategy.
- GetStrategy() str | None[source]
Return the currently selected RobotBlockSet control strategy.
- Returns:
Name of the active control strategy.
- Return type:
str | None
- AvailableStrategies() List[str][source]
List the control strategies supported by the ROS robot wrapper.
- Returns:
Available RobotBlockSet control strategies.
- Return type:
list[str]
- SetStrategy(new_strategy: str) bool | None[source]
Switch the active ROS controller to match a RobotBlockSet strategy.
- Parameters:
new_strategy (str) – Requested RobotBlockSet control strategy.
- Returns:
Falseif no switch was needed or if switching failed. ReturnsNonewhen the switch succeeds.- Return type:
bool | None
Notes
Existing motion is stopped before switching controllers.
- SetLoggerLevel(level: str = 'info', logger: str | None = None) None[source]
Set the ROS logger verbosity level for the active controller.
- Parameters:
level (str, optional) – Target logger level.
logger (str, optional) – Explicit logger name. If
None, use the active controller logger.
- GoTo_q(q: ndarray, qdot: ndarray, trq: ndarray, wait: float, **kwargs: Any) int[source]
Command the robot in joint space through the active ROS controller.
- Parameters:
q (JointConfigurationType) – Desired joint positions.
qdot (JointVelocityType) – Desired joint velocities.
trq (JointTorqueType) – Desired joint torques.
wait (float) – Synchronization time after the command is sent.
- Returns:
Motion result code.
- Return type:
int
- GoTo_X(x: ndarray, xdot: ndarray, trq: ndarray, wait: float, do_not_publish_msg: bool = False, **kwargs: Any) int[source]
Command the robot in Cartesian space through the active ROS controller.
- Parameters:
x (Pose3DType) – Desired Cartesian pose.
xdot (Velocity3DType) – Desired Cartesian twist.
trq (WrenchType) – Desired end-effector wrench.
wait (float) – Synchronization time after the command is sent.
do_not_publish_msg (bool, optional) – Legacy flag kept for compatibility.
**kwargs (Any) – Additional controller-specific keyword arguments.
- Returns:
Motion result code.
- Return type:
int
Classes
|
Base class for ROS-backed robot interfaces. |