rclpy_message_converter.message_converter module
- rclpy_message_converter.message_converter.convert_dictionary_to_ros_message(message_type: Any, dictionary: Dict[str, Any], kind: str = 'message', strict_mode: bool = True, check_missing_fields: bool = False) Any
Takes in the message type and a Python dictionary and returns a ROS message.
- Parameters:
message_type – Either the type name of the ROS message to return (as str), or the message class.
dictionary – The values to set in the ROS message. The keys of the dictionary represent fields of the message.
kind – Whether to create a message, service request or service response (valid values: “message”, “request”, “response”).
strict_mode – If strict_mode is set, an AttributeError will be raised if the input dictionary contains extra fields that are not present in the ROS message.
check_missing_fields – If this parameter is set, a ValueError will be raised if the input dictionary is missing an entry for some field of the ROS message.
- Raises:
AttributeError – If the message does not have a field provided in the input dictionary.
TypeError – If a message value does not match its field type.
ValueError – If the input dictionary is incomplete (i.e., is missing an entry for some field of the ROS message) or if an invalid value was passed to kind.
- Example:
>>> msg_type = "std_msgs/msg/String" >>> dict_msg = { "data": "Hello, Robot" } >>> convert_dictionary_to_ros_message(msg_type, dict_msg) std_msgs.msg.String(data='Hello, Robot')
>>> import std_msgs.msg >>> msg_type = std_msgs.msg.String >>> dict_msg = { "data": "Hello, Robot" } >>> convert_dictionary_to_ros_message(msg_type, dict_msg) std_msgs.msg.String(data='Hello, Robot')
>>> msg_type = "std_srvs/srv/SetBool" >>> dict_msg = { "data": True } >>> kind = "request" >>> convert_dictionary_to_ros_message(msg_type, dict_msg, kind) std_srvs.srv.SetBool_Request(data=True)
- rclpy_message_converter.message_converter.convert_ros_message_to_dictionary(message: Any, base64_encoding: bool = True) OrderedDict
Takes in a ROS message and returns an OrderedDict.
- Example:
>>> import std_msgs.msg >>> ros_message = std_msgs.msg.UInt32(data=42) >>> convert_ros_message_to_dictionary(ros_message) OrderedDict([('data', 42)])
- rclpy_message_converter.message_converter.message_to_ordereddict(msg: Any, *, base64_encoding: bool = True, truncate_length: int | None = None, no_arr: bool = False, no_str: bool = False) OrderedDict
Convert a ROS message to an OrderedDict.
This method was copied and modified from rosidl_runtime_py.convert.message_to_ordereddict.
- Parameters:
msg – The ROS message to convert.
base64_encoding – If this parameter is true, encode all variable-size uint8[] or fixed-size uint8[n] fields using Base64 encoding. This saves a lot of space when converting large messages (such as sensor_msgs/Image) to json format. If this parameter is False, these fields will be converted to array.array (for variable-size fields) or numpy.ndarray (for fixed-size fields) instead.
truncate_length – Truncate values for all message fields to this length. This does not truncate the list of fields (ie. the dictionary keys).
no_arr – Exclude array fields of the message.
no_str – Exclude string fields of the message.
- Returns:
An OrderedDict where the keys are the ROS message fields and the values are set to the values of the input message.
- rclpy_message_converter.message_converter.set_message_fields(msg: Any, values: Dict[str, Any], strict_mode: bool = True, check_missing_fields: bool = False) None
Set the fields of a ROS message.
This method was copied and modified from rosidl_runtime_py.set_message.set_message_fields .
- Parameters:
msg – The ROS message to populate.
values – The values to set in the ROS message. The keys of the dictionary represent fields of the message.
strict_mode – If strict_mode is set, an AttributeError will be raised if the input dictionary contains extra fields that are not present in the ROS message.
check_missing_fields – If this parameter is set, a ValueError will be raised if the input dictionary is missing an entry for some field of the ROS message.
- Raises:
AttributeError – If the message does not have a field provided in the input dictionary.
TypeError – If a message value does not match its field type.
ValueError – If the input dictionary is incomplete (i.e., is missing an entry for some field of the ROS message).