Reference

Array manipulation

criutils.array.unique(data)[source]

Find the unique elements of an array row-wise and returns the sorted unique elements of an array.

Parameters:data (array_like) – Input array.
Returns:res – The sorted unique array.
Return type:array_like

Conversions

criutils.conversions.from_dict(transform_dict)[source]

Converts a dictionary with the fields rotation and translation into a homogeneous transformation.

Parameters:transform_dict (dict) – The dictionary to be converted
Returns:array – The resulting numpy array
Return type:array_like
criutils.conversions.from_point(msg)[source]

Convert a geometry_msgs/Point ROS message into a numpy array.

Parameters:msg (geometry_msgs/Point) – The ROS message to be converted
Returns:array – The resulting numpy array
Return type:np.array
criutils.conversions.from_pose(msg)[source]

Convert a geometry_msgs/Pose ROS message into a numpy array (4x4 homogeneous transformation).

Parameters:msg (geometry_msgs/Pose) – The ROS message to be converted
Returns:array – The resulting numpy array
Return type:np.array
criutils.conversions.from_quaternion(msg)[source]

Convert a geometry_msgs/Quaternion ROS message into a numpy array.

Parameters:msg (geometry_msgs/Quaternion) – The ROS message to be converted
Returns:array – The resulting numpy array
Return type:np.array
criutils.conversions.from_roi(msg)[source]

Convert a sensor_msgs/RegionOfInterest ROS message into a list with the two corners of the ROI.

Parameters:msg (sensor_msgs/RegionOfInterest) – The ROS message to be converted
Returns:result – The resulting list
Return type:list
criutils.conversions.from_transform(msg)[source]

Convert a geometry_msgs/Transform ROS message into a numpy array (4x4 homogeneous transformation).

Parameters:msg (geometry_msgs/Transform) – The ROS message to be converted
Returns:array – The resulting numpy array
Return type:np.array
criutils.conversions.from_vector3(msg)[source]

Convert a geometry_msgs/Vector3 ROS message into a numpy array.

Parameters:msg (geometry_msgs/Vector3) – The ROS message to be converted
Returns:array – The resulting numpy array
Return type:np.array
criutils.conversions.from_wrench(msg)[source]

Convert a geometry_msgs/Wrench ROS message into a numpy array.

Parameters:msg (geometry_msgs/Wrench) – The ROS message to be converted
Returns:array – The resulting numpy array
Return type:np.array
criutils.conversions.to_point(array)[source]

Convert a numpy array XYZ into a geometry_msgs/Point ROS message.

Parameters:array (np.array) – The position XYZ as numpy array
Returns:msg – The resulting ROS message
Return type:geometry_msgs/Point
criutils.conversions.to_pose(T)[source]

Convert a homogeneous transformation (4x4) into a geometry_msgs/Pose ROS message.

Parameters:T (np.array) – The homogeneous transformation
Returns:msg – The resulting ROS message
Return type:geometry_msgs/Pose
criutils.conversions.to_quaternion(array)[source]

Convert a numpy array WXYZ into a geometry_msgs/Quaternion ROS message.

Parameters:array (np.array) – The quaternion XYZW as numpy array
Returns:msg – The resulting ROS message
Return type:geometry_msgs/Quaternion
criutils.conversions.to_roi(top_left, bottom_right)[source]

Generate a sensor_msgs/RegionOfInterest ROS message using the two given corners

Parameters:
  • top_left (array_like) – The top left corner of the ROI
  • bottom_right (array_like) – The bottom right corner of the ROI
Returns:

msg – The resulting ROS message

Return type:

sensor_msgs/RegionOfInterest

criutils.conversions.to_transform(T)[source]

Convert a homogeneous transformation (4x4) into a geometry_msgs/Transform ROS message.

Parameters:T (np.array) – The homogeneous transformation
Returns:msg – The resulting ROS message
Return type:geometry_msgs/Transform
criutils.conversions.to_vector3(array)[source]

Convert a numpy array XYZ into a geometry_msgs/Vector3 ROS message.

Parameters:array (array_like) – The vector XYZ as numpy array
Returns:msg – The resulting ROS message
Return type:geometry_msgs/Vector3
criutils.conversions.to_wrench(array)[source]

Convert a numpy array into a geometry_msgs/Wrench ROS message.

Parameters:array (array_like) – The wrench \([f_x, f_y, f_z, t_x, t_y, t_z]\) as numpy array
Returns:msg – The resulting ROS message
Return type:geometry_msgs/Wrench

Logger

class criutils.logger.ColoredFormatter(formatter)[source]

Bases: logging.Formatter

A formatter that allows colors to be placed in the format string.

Intended to help in creating more readable logging output.

format(record)[source]

Customize the message format based on the log level.

criutils.logger.initialize_logging(spammy_level=30, format_level=10)[source]

Initialize and configure loggers to disable spammy and ROS loggers

Parameters:
  • spammy_level (int) – Spammy and ROS loggers below this logging level are disabled. Default: logging.WARNING
  • format_level (int) – Logging level to be use for this logger Default: logging.DEBUG
Returns:

base_logger – The base/root logger

Return type:

logging.RootLogger

criutils.logger.remove_ros_logger()[source]

Remove ROS logger

Parameter Server

criutils.parameter.read_parameter(name, default)[source]

Get a parameter from the ROS parameter server. If it’s not found, a warning is printed.

Parameters:
  • name (string) – Parameter name
  • default (Object) – Default value for the parameter. The type of the default object defines the type of the parameter
Returns:

value – If found, the read parameter. Otherwise, default is returned.

Return type:

Object

RViz

criutils.rviz.create_interactive_6dof(name, color=(1, 0, 0, 1), frame_id='base_link', transform=None, scale=0.05)[source]

Create a 6-DoF interactive marker

Parameters:
  • name (string) – Marker name
  • color (array_like) – Marker color is a 4 elements iterable to be used as RGBA color
  • frame_id (str) – Reference frame of the marker frame. This a frame that must exist in TF
  • transform (array_like) – Homogenous transformation (4x4) of the marker with respect to the reference frame frame_id
  • scale (float) – Scale of the marker applied before the position/orientation.
Returns:

int_marker – The 6-DoF interactive marker

Return type:

visualization_msgs.InteractiveMarker

criutils.rviz.create_interactive_mesh(name, resource, color=(1, 0, 0, 1), frame_id='base_link', transform=None, scale=1.0)[source]

Create an interactive marker which includes a mesh

Parameters:
  • name (string) – Marker name
  • resource (string) – The format is the URI-form used by resource_retriever, including the package:// syntax.
  • color (array_like) – Marker color is a 4 elements iterable to be used as RGBA color
  • frame_id (str) – Reference frame of the marker frame. This a frame that must exist in TF
  • transform (array_like) – Homogenous transformation (4x4) of the marker with respect to the reference frame frame_id
  • scale (float) – Scale of the marker applied before the position/orientation.
Returns:

int_marker – The interactive mesh marker

Return type:

visualization_msgs.InteractiveMarker

criutils.rviz.create_mesh_marker(mrkid, name, resource, color=(1, 0, 0, 1), ns='', frame_id='base_link', transform=None, scale=1)[source]

Create a mesh marker

Parameters:
  • mrkid (int) – Unique id assigned to this marker. It is your responsibility to keep these unique within your namespace.
  • name (string) – Marker name
  • resource (string) –

    The format is the URI-form used by resource_retriever, including the package:// syntax.

  • color (array_like) – Marker color is a 4 elements iterable to be used as RGBA color
  • ns (str) – Namespace for these markers. This plus the mrkid form a unique identifier.
  • frame_id (str) – Reference frame of the marker frame. This a frame that must exist in TF
  • transform (array_like) – Homogenous transformation (4x4) of the marker with respect to the reference frame frame_id
  • scale (float) – Scale of the marker applied before the position/orientation.
Returns:

marker – The mesh marker

Return type:

visualization_msgs.Marker

criutils.rviz.create_points_marker(mrkid, points, size=0.001, color=(1, 0, 0, 1), ns='', frame_id='base_link', transform=None)[source]

Create a marker of points

Parameters:
  • mrkid (int) – Unique id assigned to this marker. It is your responsibility to keep these unique within your namespace.
  • points (list) – The list of XYZ points
  • size (float) – Point width and height (pixels)
  • color (array_like) – Marker color is a 4 elements iterable to be used as RGBA color
  • ns (str) – Namespace for these markers. This plus the mrkid form a unique identifier.
  • frame_id (str) – Reference frame of the marker frame. This a frame that must exist in TF
  • transform (array_like) – Homogenous transformation (4x4) of the marker with respect to the reference frame frame_id
Returns:

marker – The marker of points

Return type:

visualization_msgs.Marker

criutils.rviz.create_text_marker(mrkid, text, size=0.02, color=(1, 0, 0, 1), ns='', frame_id='base_link', position=None)[source]

Create a text marker. The text always appears oriented correctly to the view.

Parameters:
  • mrkid (int) – Unique id assigned to this marker. It is your responsibility to keep these unique within your namespace.
  • text (string) – The marker text
  • size (float) – Specifies the height of an uppercase “A” (meters)
  • color (array_like) – Marker color is a 4 elements iterable to be used as RGBA color
  • ns (str) – Namespace for these markers. This plus the mrkid form a unique identifier.
  • frame_id (str) – Reference frame of the marker frame. This a frame that must exist in TF
  • position (array_like) – XYZ position of the text marker with respect to the reference frame frame_id. If it’s not indicated, the text will be place at \([0, 0, 0]\)
Returns:

marker – The text marker

Return type:

visualization_msgs.Marker

criutils.rviz.get_safe_stamp()[source]

Get a safe stamp.

It’s useful when ROS time hasn’t been initialized then this will return a rospy.Time equal to zero.

Returns:stamp – The safe stamp
Return type:rospy.Time