controllers_ros
ROS controller interface implementations.
This module defines ROS-backed controller wrappers used by RobotBlockSet robot interfaces. It provides helpers for controller-manager interaction, joint-space impedance commands, and Cartesian impedance commands through ROS topics, actions, and service proxies.
- class robotblockset.ros.controllers_ros.ros_controller_interface(ros_controller_name: str, ros_logger_name: str)[source]
Bases:
rbs_objectBase class for ROS-backed controller interfaces.
- Attributes:
_ros_controller_name (str) – Name of the ROS controller resource managed by the interface.
_ros_logger_name (str) – Name of the ROS logger associated with the controller.
Initialize the ROS controller interface base.
- Parameters:
ros_controller_name (str) – Name of the ROS controller resource.
ros_logger_name (str) – Name of the ROS logger associated with the controller.
- Returns:
This constructor initializes the ROS controller interface in place.
- Return type:
None
- __init__(ros_controller_name: str, ros_logger_name: str) None[source]
Initialize the ROS controller interface base.
- Parameters:
ros_controller_name (str) – Name of the ROS controller resource.
ros_logger_name (str) – Name of the ROS logger associated with the controller.
- Returns:
This constructor initializes the ROS controller interface in place.
- Return type:
None
- class robotblockset.ros.controllers_ros.controller_manager_proxy(controller_manager_node_location: str = 'controller_manager', robot_resource_name: str = 'panda')[source]
Bases:
objectProxy around ROS controller-manager services.
- Attributes:
robot_resource_name (str) – Resource name used to identify controllers that belong to the robot.
controller_manager_node_location (str) – ROS namespace of the controller-manager node.
current_controller (str) – Name of the currently active controller, if known.
_last_controller (str) – Name of the last active controller remembered for restart.
Create a proxy for ROS controller-manager services.
- Parameters:
controller_manager_node_location (str, optional) – ROS namespace of the controller manager.
robot_resource_name (str, optional) – Resource name used to identify robot-specific controllers.
- __init__(controller_manager_node_location: str = 'controller_manager', robot_resource_name: str = 'panda') None[source]
Create a proxy for ROS controller-manager services.
- Parameters:
controller_manager_node_location (str, optional) – ROS namespace of the controller manager.
robot_resource_name (str, optional) – Resource name used to identify robot-specific controllers.
- update_active_controller() str[source]
Query the active controller that claims the configured robot resource.
- Returns:
Name of the active controller, or an empty string if none was found.
- Return type:
str
- list_loaded_controllers() List[str][source]
List names of controllers known to the controller manager.
- Returns:
Names of all controllers reported by the controller manager.
- Return type:
list[str]
- switch_controller(start_controllers: List[str], stop_controllers: List[str], strictness: int = 1) bool[source]
Switch the active controller set.
- Parameters:
start_controllers (list[str]) – Names of controllers to start.
stop_controllers (list[str]) – Names of controllers to stop.
strictness (int, optional) – ROS controller-manager strictness level.
1means best effort and2means strict.
- Returns:
Trueif the switch request succeeded, otherwiseFalse.- Return type:
bool
- load_controller(controller_name: str) bool[source]
Load a controller through the controller manager.
- Parameters:
controller_name (str) – Name of the controller to load.
- Returns:
Trueif the controller was loaded successfully, otherwiseFalse.- Return type:
bool
- unload_controller(controller_name: str) bool[source]
Unload a controller through the controller manager.
- Parameters:
controller_name (str) – Name of the controller to unload.
- Returns:
Trueif the controller was unloaded successfully, otherwiseFalse.- Return type:
bool
- stop_active_controller() bool[source]
Stop the currently active controller and remember it for restart.
- Returns:
Trueif the stop request succeeded, otherwiseFalse.- Return type:
bool
- start_last_controller() bool[source]
Restart the last controller stopped by stop_active_controller.
- Returns:
Trueif the start request succeeded, otherwiseFalse.- Return type:
bool
- class robotblockset.ros.controllers_ros.joint_impedance_controller(robot: Any | None = None, namespace: str | None = None, ros_controller_name: str = 'joint_impedance_controller', ros_logger_name: str = 'ros.ijs_controllers')[source]
Bases:
ros_controller_interface,joint_controller_typeROS joint-impedance controller wrapper.
- Attributes:
_ns (str) – Fully qualified ROS namespace for the controller topics.
_robot (Any) – Robot instance associated with the controller.
joint_command_publisher (rospy.Publisher) – Publisher used to send joint command messages.
joint_action_client (actionlib.SimpleActionClient) – Action client used for trapezoidal-velocity joint moves.
joint_impedance_reset_client (rospy.Publisher) – Publisher used to reset the controller target.
_joint_command_msg (JointCommand) – Reusable command message instance.
Initialize the ROS joint-impedance controller wrapper.
- Parameters:
robot (Any, optional) – Robot instance associated with the controller.
namespace (str, optional) – Namespace prefix used to resolve controller topics.
ros_controller_name (str, optional) – Name of the ROS controller resource.
ros_logger_name (str, optional) – Name of the ROS logger associated with the controller.
- __init__(robot: Any | None = None, namespace: str | None = None, ros_controller_name: str = 'joint_impedance_controller', ros_logger_name: str = 'ros.ijs_controllers') None[source]
Initialize the ROS joint-impedance controller wrapper.
- Parameters:
robot (Any, optional) – Robot instance associated with the controller.
namespace (str, optional) – Namespace prefix used to resolve controller topics.
ros_controller_name (str, optional) – Name of the ROS controller resource.
ros_logger_name (str, optional) – Name of the ROS logger associated with the controller.
- GoTo_q(q: ndarray, qdot: ndarray, trq: ndarray, **kwargs: Any) None[source]
Publish a joint-space command to the impedance controller.
- Parameters:
q (JointConfigurationType) – Joint-position target.
qdot (JointVelocityType) – Joint-velocity target.
trq (JointTorqueType) – Joint-torque feedforward command.
- Return type:
None
- SetJointCompliance(K: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, D: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, hold_pose: bool = True) None[source]
Update the commanded joint impedance parameters.
- Parameters:
K (ArrayLike, optional) – Desired joint stiffness values. Scalars are broadcast to all joints.
D (ArrayLike, optional) – Desired joint damping values. Scalars are broadcast to all joints.
hold_pose (bool, optional) – If
True, reset the current target and apply the new compliance at the current commanded pose.
- Return type:
None
Notes
When
hold_poseisFalse, the stiffness is ramped in steps to avoid abrupt changes in commanded impedance.
- class robotblockset.ros.controllers_ros.cartesian_impedance_controller(robot: Any | None = None, namespace: str | None = None, ros_controller_name: str = 'cartesian_impedance_controller', ros_logger_name: str = 'ros.ijs_controllers')[source]
Bases:
ros_controller_interface,cartesian_controller_typeROS Cartesian-impedance controller wrapper.
- Attributes:
_ns (str) – Fully qualified ROS namespace for the controller topics.
_robot (Any) – Robot instance associated with the controller.
cart_activate_publisher (rospy.Publisher) – Publisher used to enable the Cartesian controller.
cartesian_command_publisher (rospy.Publisher) – Publisher used to send Cartesian command messages.
cart_null_q_publisher (rospy.Publisher) – Publisher used to send null-space joint targets.
cart_null_k_publisher (rospy.Publisher) – Publisher used to send null-space stiffness values.
reset_target_svc (rospy.Publisher) – Publisher used to reset the controller target.
cart_stiff_publisher (rospy.Publisher) – Publisher used to send stiffness-only updates.
_cartesian_command_msg (CartesianCommand) – Reusable Cartesian command message instance.
_impedance_parameters_msg (ImpedanceParameters) – Reusable impedance message instance.
Initialize the ROS Cartesian-impedance controller wrapper.
- Parameters:
robot (Any, optional) – Robot instance associated with the controller.
namespace (str, optional) – Namespace prefix used to resolve controller topics.
ros_controller_name (str, optional) – Name of the ROS controller resource.
ros_logger_name (str, optional) – Name of the ROS logger associated with the controller.
- __init__(robot: Any | None = None, namespace: str | None = None, ros_controller_name: str = 'cartesian_impedance_controller', ros_logger_name: str = 'ros.ijs_controllers') None[source]
Initialize the ROS Cartesian-impedance controller wrapper.
- Parameters:
robot (Any, optional) – Robot instance associated with the controller.
namespace (str, optional) – Namespace prefix used to resolve controller topics.
ros_controller_name (str, optional) – Name of the ROS controller resource.
ros_logger_name (str, optional) – Name of the ROS logger associated with the controller.
- GoTo_X(x: ndarray, xdot: ndarray, trq: ndarray, wait: float, **kwargs: Any) None[source]
Publish a Cartesian command to the impedance controller.
- Parameters:
x (Pose3DType) – Cartesian pose target expressed as position and quaternion.
xdot (Velocity3DType) – Cartesian twist command.
trq (WrenchType) – End-effector wrench command.
wait (float) – Wait time associated with the command.
**kwargs (Any) – Optional Cartesian compliance overrides:
Kp,Kr,R, andD.
- Return type:
None
- SetCartImpContNullspace(q: ndarray, k: ndarray) None[source]
Set null-space target and stiffness for the Cartesian controller.
- Parameters:
q (JointConfigurationType) – Null-space joint target.
k (JointConfigurationType) – Null-space stiffness values.
- Return type:
None
- GetCartImpContNullspace() Tuple[ndarray, ndarray][source]
Return the Cartesian-controller null-space target and stiffness.
- Returns:
Tuple containing the stored null-space target and stiffness vectors.
- Return type:
tuple[JointConfigurationType, JointConfigurationType]
- SetCartesianCompliance(Kp: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, Kr: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, R: ndarray | None = None, D: float | None = None, hold_pose: bool = True) int[source]
Update the commanded Cartesian impedance parameters.
- Parameters:
Kp (ArrayLike, optional) – Translational stiffness values. Scalars are broadcast to three axes.
Kr (ArrayLike, optional) – Rotational stiffness values. Scalars are broadcast to three axes.
R (RotationMatrixType, optional) – Rotation matrix used to orient translational stiffness.
D (float, optional) – Damping factor in the interval
[0, 2].hold_pose (bool, optional) – If
True, update compliance while holding the current target pose.
- Returns:
0when the compliance update was accepted.- Return type:
int
Notes
The method updates both the outgoing ROS impedance message and the cached compliance values stored on the attached robot object.
Classes
|
ROS Cartesian-impedance controller wrapper. |
|
Proxy around ROS controller-manager services. |
|
ROS joint-impedance controller wrapper. |
Base class for ROS-backed controller interfaces. |