platforms_ros

ROS platform interface implementations.

This module defines ROS-backed platform wrappers used by RobotBlockSet mobile platform interfaces. It provides localization, navigation, obstacle sensing, map visualization, and base-motion helpers through ROS topics and services.

robotblockset.ros.platforms_ros.plot_map(platform_pose: ndarray | None = None, scan_msg: sensor_msgs.msg.LaserScan | None = None, map_msg: Any | None = None, map_frame: ndarray | None = None, in_map_frame: bool = False) None[source]

Plot the map, robot pose, and laser scan points.

Parameters:
  • platform_pose (np.ndarray, optional) – The 2D pose of the platform in the format (x, y, theta). Defaults to (0, 0, 0).

  • scan_msg (LaserScan, optional) – The received laser scan message.

  • map_msg (OccupancyGrid, optional) – The received occupancy grid message.

  • map_frame (np.ndarray, optional) – The origin of the map in the world frame as (x, y, theta). Defaults to (0, 0, 0).

  • in_map_frame (bool, optional) – If True, display the scene in the map frame instead of the world frame. Defaults to False.

Returns:

This function renders the map and sensor data using Matplotlib.

Return type:

None

Notes

The plot is intended for debugging and visualization and does not modify the platform state.

class robotblockset.ros.platforms_ros.platform_ros(name: str = '', ns: str = '', init_node: bool = True, multi_node: bool = False)[source]

Bases: platform

Base class for ROS-backed mobile platform interfaces.

Attributes:

_namespace (str) – ROS namespace prefix used by the platform wrapper.

Initialize the generic ROS platform interface.

Parameters:
  • name (str, optional) – Name of the platform.

  • ns (str, optional) – ROS namespace of the platform.

  • 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.

__init__(name: str = '', ns: str = '', init_node: bool = True, multi_node: bool = False) None[source]

Initialize the generic ROS platform interface.

Parameters:
  • name (str, optional) – Name of the platform.

  • ns (str, optional) – ROS namespace of the platform.

  • 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.

is_ros_ready() bool[source]

Return whether the ROS node for the platform is active.

Returns:

True if the ROS node is active.

Return type:

bool

SetLocation(x_init: Any, theta_init: float | None = None, cov_init: ndarray | None = None) None[source]

Sets the platform’s initial location in the map frame.

This function updates the platform’s pose and publishes it to the localization topic.

Parameters:
  • x_init (array-like) – The initial position (x, y) or (x, y, theta) of the platform.

  • theta_init (float, optional) – The initial orientation (theta) of the platform. If None, it is extracted from x_init.

  • cov_init (np.ndarray, optional) – The covariance matrix of the initial pose. Defaults to a diagonal matrix with small uncertainty.

Returns:

This method publishes a new initial pose for localization.

Return type:

None

SetNavigationMode(mode: str = 'MAP') Tuple[bool, str][source]

Sets the navigation mode of the platform.

This function switches the navigation mode between map-based (MAP) and localization-based (LOC).

Parameters:

mode (str, optional) – The navigation mode, either “MAP” or “LOC”. Defaults to “MAP”.

Returns:

A boolean indicating success and an error message if applicable.

Return type:

tuple (bool, str)

GetSLAMLocation(out: str | None = None, task_space: str | None = None, state: Any | None = None) ndarray[source]

Retrieves the current SLAM-based location of the platform.

This function fetches the latest SLAM pose information, checks its validity, and transforms it into the desired output format.

Parameters:
  • out (str, optional) – The format of the output location. Defaults to the platform’s task pose form.

  • task_space (str, optional) – Defines the task space in which the pose should be returned. (To be implemented).

  • state (any, optional) – Additional state information (currently not used).

Returns:

The transformed SLAM pose in the requested format. If SLAM data is unavailable, returns an array of NaN values.

Return type:

np.ndarray

CMoveToLocAMCL(rp: Any, rtheta: float | None = None, task_space: str = 'World') int[source]

Moves the platform to a specified location using AMCL localization.

Parameters:
  • rp (array-like) – The target position (x, y) or (x, y, theta) in the specified task space.

  • rtheta (float, optional) – The target orientation. If None, it is extracted from rp.

  • task_space (str, optional) – The task space for the movement. Options: “World”, “Object”, “Platform”. Defaults to “World”.

Returns:

Error status (0 if successful, nonzero if failed).

Return type:

int

OMoveToLocAMCL(rp: Any, rtheta: float) int[source]

Moves the platform to an object-relative location using AMCL localization.

Returns:

Motion status code returned by CMoveToLocAMCL.

Return type:

int

PMoveToLocAMCL(rp: Any, rtheta: float) int[source]

Moves the platform to a platform-relative location using AMCL localization.

Returns:

Motion status code returned by CMoveToLocAMCL.

Return type:

int

GetClosestFrontObstacle(ang_range: Any | None = None, for_platform: bool | None = None) Tuple[float, float][source]

Finds the closest obstacle in the front laser scan within a specified angular range.

Parameters:
  • ang_range (float or array-like, optional) – If None, uses the default laser angle range. If scalar, it defines a symmetric range around zero. If a 2-element array, it specifies the range directly. Defaults to None.

  • for_platform (bool, optional) – If True, calculates distance of platform in forward direction . If False, uses raw laser sensor data. Defaults to True.

Returns:

The minimum detected distance and its corresponding angle.

Return type:

tuple (float, float)

GetClosestRearObstacle() float[source]

Finds the closest obstacle detected by the rear sonar sensor.

Returns:

The measured distance to the closest rear obstacle. Returns infinity if no reading is available.

Return type:

float

GetClosestObstacle(ang_range: Any = [-3.141592653589793, 3.141592653589793]) float[source]

Finds the closest obstacle detected by either the front laser scanner or the rear sonar sensor.

Parameters:

ang_range (array-like, optional) – The angular range for front obstacle detection. Defaults to [-pi, pi].

Returns:

The minimum detected obstacle distance from either the front or rear sensor.

Return type:

float

PlotObstacles(ang_range: Any | None = None) None[source]

Plot laser-scan obstacles and closest platform distances.

Check(silent: bool = False) list[str][source]

Check the current platform status.

Parameters:

silent (bool, optional) – If True, suppress status messages while checking the platform.

Returns:

List of active platform errors.

Return type:

list[str]

HasError() bool[source]

Return whether the platform currently reports any errors.

class robotblockset.ros.platforms_ros.tiagobase(name: str = 'TiagoBase', ns: str = '', localization: str | None = None, natnet_platform_rigidbody_id: int = 1, natnet_host_ip: str = '127.0.0.1', natnet_client_ip: str = '127.0.0.1', natnet_multicast_ip: str = '239.255.42.99')[source]

Bases: tiagobase_spec, platform_ros

ROS interface for the Tiago base platform.

Attributes:
  • localization (str) – Active localization mode, for example "SLAM" or "OPTI".

  • opti (optitrack_localization | None) – OptiTrack localization helper.

  • TOPTIFrame (np.ndarray) – Transform defining the OptiTrack world frame.

Initialize the Tiago base ROS interface.

Parameters:
  • name (str, optional) – Name of the platform.

  • ns (str, optional) – ROS namespace of the platform.

  • localization (str, optional) – Initial localization mode.

  • natnet_platform_rigidbody_id (int, optional) – NatNet rigid-body identifier used by OptiTrack.

  • natnet_host_ip (str, optional) – NatNet host IP address.

  • natnet_client_ip (str, optional) – NatNet client IP address.

  • natnet_multicast_ip (str, optional) – NatNet multicast IP address.

__init__(name: str = 'TiagoBase', ns: str = '', localization: str | None = None, natnet_platform_rigidbody_id: int = 1, natnet_host_ip: str = '127.0.0.1', natnet_client_ip: str = '127.0.0.1', natnet_multicast_ip: str = '239.255.42.99') None[source]

Initialize the Tiago base ROS interface.

Parameters:
  • name (str, optional) – Name of the platform.

  • ns (str, optional) – ROS namespace of the platform.

  • localization (str, optional) – Initial localization mode.

  • natnet_platform_rigidbody_id (int, optional) – NatNet rigid-body identifier used by OptiTrack.

  • natnet_host_ip (str, optional) – NatNet host IP address.

  • natnet_client_ip (str, optional) – NatNet client IP address.

  • natnet_multicast_ip (str, optional) – NatNet multicast IP address.

SetOPTIFrame(x: Any) None[source]

Set the OptiTrack world frame used by the platform.

Parameters:

x (Any) – Pose specification accepted by spatial().

GetOPTIFrame(out: str | None = None) Any[source]

Return the configured OptiTrack world frame.

Parameters:

out (str, optional) – Requested output pose format.

Returns:

OptiTrack world frame in the requested format.

Return type:

Any

GetState() None[source]

Update the platform state from ROS localization and sensor topics.

Notes

The method updates wheel state, localization, obstacle sensors, and the base pose of an attached robot, if present.

Set_vel(v: Any, wait: float | None = None) None[source]

Command planar platform velocity and wait.

Parameters:
  • v (Any) – Desired planar velocity (forward, turn).

  • wait (float, optional) – Duration for which the command should be maintained.

Returns:

This method publishes a planar velocity command.

Return type:

None

SetLocalization(localization: str = 'SLAM', natnet_host_ip: str | None = None, natnet_client_ip: str | None = None, natnet_multicast_ip: str | None = None) None[source]

Select SLAM or OptiTrack localization for the platform.

Parameters:
  • localization (str, optional) – Requested localization mode.

  • natnet_host_ip (str, optional) – Optional NatNet host IP override.

  • natnet_client_ip (str, optional) – Optional NatNet client IP override.

  • natnet_multicast_ip (str, optional) – Optional NatNet multicast IP override.

GetMapLocation(out: str = '2d') Any[source]

Retrieves the current location the map frame.

This function computes the transformation between the SLAM and OPTI frames and returns the mapped pose of the map.

Parameters:

out (str, optional) – The format of the output location, default is “2d”.

Returns:

If localization data is available, returns the transformed pose in the desired format. Otherwise, returns NaN.

Return type:

np.ndarray or float

SetSLAMFrame(x: Any | None = None) None[source]

Set the SLAM frame transform used by the platform wrapper.

Parameters:

x (Any, optional) – Pose specification of the SLAM frame transform.

Functions

plot_map([platform_pose, scan_msg, map_msg, ...])

Plot the map, robot pose, and laser scan points.

Classes

platform_ros([name, ns, init_node, multi_node])

Base class for ROS-backed mobile platform interfaces.

tiagobase([name, ns, localization, ...])

ROS interface for the Tiago base platform.