Functions | Variables
rospy_message_converter::message_converter Namespace Reference

Functions

def _convert_from_ros_array
def _convert_from_ros_binary
def _convert_from_ros_primitive
def _convert_from_ros_time
def _convert_from_ros_type
def _convert_to_ros_array
def _convert_to_ros_binary
def _convert_to_ros_primitive
def _convert_to_ros_time
def _convert_to_ros_type
def _get_message_fields
def _is_field_type_an_array
def convert_dictionary_to_ros_message
def convert_ros_message_to_dictionary
def is_ros_binary_type

Variables

tuple list_brackets = re.compile(r'\[[^\]]*\]')
list python_list_types = [list, tuple]
list python_primitive_types = [bool, int, long, float]
list python_string_types = [str, unicode]
dictionary python_to_ros_type_map
tuple ros_binary_types_regexp = re.compile(r'(uint8|char)\[[^\]]*\]')
list ros_header_types = ['Header', 'std_msgs/Header', 'roslib/Header']
list ros_primitive_types
list ros_time_types = ['time', 'duration']

Function Documentation

def rospy_message_converter.message_converter._convert_from_ros_array (   field_type,
  field_value 
) [private]

Definition at line 199 of file message_converter.py.

def rospy_message_converter.message_converter._convert_from_ros_binary (   field_type,
  field_value 
) [private]

Definition at line 185 of file message_converter.py.

def rospy_message_converter.message_converter._convert_from_ros_primitive (   field_type,
  field_value 
) [private]

Definition at line 196 of file message_converter.py.

def rospy_message_converter.message_converter._convert_from_ros_time (   field_type,
  field_value 
) [private]

Definition at line 189 of file message_converter.py.

def rospy_message_converter.message_converter._convert_from_ros_type (   field_type,
  field_value 
) [private]

Definition at line 152 of file message_converter.py.

def rospy_message_converter.message_converter._convert_to_ros_array (   field_type,
  list_value 
) [private]

Definition at line 132 of file message_converter.py.

def rospy_message_converter.message_converter._convert_to_ros_binary (   field_type,
  field_value 
) [private]

Definition at line 103 of file message_converter.py.

def rospy_message_converter.message_converter._convert_to_ros_primitive (   field_type,
  field_value 
) [private]

Definition at line 129 of file message_converter.py.

def rospy_message_converter.message_converter._convert_to_ros_time (   field_type,
  field_value 
) [private]

Definition at line 112 of file message_converter.py.

def rospy_message_converter.message_converter._convert_to_ros_type (   field_type,
  field_value 
) [private]

Definition at line 89 of file message_converter.py.

Definition at line 203 of file message_converter.py.

Definition at line 206 of file message_converter.py.

Takes in the message type and a Python dictionary and returns a ROS message.

Example:
    message_type = "std_msgs/String"
    dict_message = { "data": "Hello, Robot" }
    ros_message = convert_dictionary_to_ros_message(message_type, dict_message)

Definition at line 64 of file message_converter.py.

Takes in a ROS message and returns a Python dictionary.

Example:
    ros_message = std_msgs.msg.String(data="Hello, Robot")
    dict_message = convert_ros_message_to_dictionary(ros_message)

Definition at line 136 of file message_converter.py.

def rospy_message_converter.message_converter.is_ros_binary_type (   field_type,
  field_value 
)
Checks if the field is a binary array one, fixed size or not

is_ros_binary_type("uint8", 42)
>>> False
is_ros_binary_type("uint8[]", [42, 18])
>>> True
is_ros_binary_type("uint8[3]", [42, 18, 21]
>>> True
is_ros_binary_type("char", 42)
>>> False
is_ros_binary_type("char[]", [42, 18])
>>> True
is_ros_binary_type("char[3]", [42, 18, 21]
>>> True

Definition at line 167 of file message_converter.py.


Variable Documentation

Definition at line 62 of file message_converter.py.

Definition at line 53 of file message_converter.py.

Definition at line 51 of file message_converter.py.

Definition at line 52 of file message_converter.py.

Initial value:
00001 {
00002     'bool'    : ['bool'],
00003     'int'     : ['int8', 'byte', 'uint8', 'char',
00004                  'int16', 'uint16', 'int32', 'uint32',
00005                  'int64', 'uint64', 'float32', 'float64'],
00006     'float'   : ['float32', 'float64'],
00007     'str'     : ['string'],
00008     'unicode' : ['string'],
00009     'long'    : ['uint64']
00010 }

Definition at line 40 of file message_converter.py.

tuple rospy_message_converter::message_converter::ros_binary_types_regexp = re.compile(r'(uint8|char)\[[^\]]*\]')

Definition at line 60 of file message_converter.py.

Definition at line 59 of file message_converter.py.

Initial value:
00001 ['bool', 'byte', 'char', 'int8', 'uint8', 'int16',
00002                        'uint16', 'int32', 'uint32', 'int64', 'uint64',
00003                        'float32', 'float64', 'string']

Definition at line 56 of file message_converter.py.

Definition at line 55 of file message_converter.py.



rospy_message_converter
Author(s): Brandon Alexander
autogenerated on Sat May 6 2017 02:31:54