ros_sugar.io.supported_types
#
ROS Topics Supported Message Types
Module Contents#
Classes#
Meta. |
|
Class used to define all supported data types (ROS messages) callback: Callback associated with specified type _publish: ROS message creation method associate with specified type |
|
String. |
|
Bool. |
|
Float32. |
|
Float32MultiArray. |
|
Float64. |
|
Float64MultiArray. |
|
Image. |
|
CompressedImage format usually provided by camera vendors |
|
Audio. |
|
MapMetaData. |
|
Odometry |
|
LaserScan |
|
Path |
|
OccupancyGrid |
|
Point |
|
PointStamped |
|
Pose |
|
PoseStamped |
|
Component Health Status |
|
Twist for Control Commands |
Functions#
Add additional SupportedType classes to the list of supported ROS2 messages |
API#
- ros_sugar.io.supported_types.add_additional_datatypes(types: List[type]) None #
Add additional SupportedType classes to the list of supported ROS2 messages
- Parameters:
types (List[type]) – List of supported types
- class ros_sugar.io.supported_types.Meta#
Bases:
type
Meta.
- class ros_sugar.io.supported_types.SupportedType#
Class used to define all supported data types (ROS messages) callback: Callback associated with specified type _publish: ROS message creation method associate with specified type
- classmethod convert(output, **_) Any #
ROS message converter function for datatype
- Parameters:
args
- Return type:
Any
- classmethod get_ros_type() type #
Getter of the ROS2 message type
- Returns:
ROS2 type
- Return type:
type
- class ros_sugar.io.supported_types.String#
Bases:
ros_sugar.io.supported_types.SupportedType
String.
- classmethod convert(output: str, **_) std_msgs.msg.String #
Takes a string and returns a ROS message of type String
- Returns:
String
- classmethod get_ros_type() type #
- class ros_sugar.io.supported_types.Bool#
Bases:
ros_sugar.io.supported_types.SupportedType
Bool.
- classmethod convert(output: bool, **_) std_msgs.msg.Bool #
Takes a bool and returns a ROS message of type Bool
- Returns:
Bool
- classmethod get_ros_type() type #
- class ros_sugar.io.supported_types.Float32#
Bases:
ros_sugar.io.supported_types.SupportedType
Float32.
- classmethod convert(output: float, **_) std_msgs.msg.Float32 #
Takes a float and returns a ROS message of type Float32
- Returns:
Float32
- classmethod get_ros_type() type #
- class ros_sugar.io.supported_types.Float32MultiArray#
Bases:
ros_sugar.io.supported_types.SupportedType
Float32MultiArray.
- classmethod convert(output: numpy.ndarray, **_) std_msgs.msg.Float32MultiArray #
Takes a numpy array and returns a ROS message of type Float32MultiArray
- Returns:
Float32
- classmethod get_ros_type() type #
- class ros_sugar.io.supported_types.Float64#
Bases:
ros_sugar.io.supported_types.SupportedType
Float64.
- classmethod convert(output: float, **_) std_msgs.msg.Float64 #
Takes a float and returns a ROS message of type Float64
- Returns:
Float64
- classmethod get_ros_type() type #
- class ros_sugar.io.supported_types.Float64MultiArray#
Bases:
ros_sugar.io.supported_types.SupportedType
Float64MultiArray.
- classmethod convert(output: numpy.ndarray, **_) std_msgs.msg.Float64MultiArray #
Takes a numpy array and returns a ROS message of type Float64MultiArray
- Returns:
Float32
- classmethod get_ros_type() type #
- class ros_sugar.io.supported_types.Image#
Bases:
ros_sugar.io.supported_types.SupportedType
Image.
- classmethod convert(output: Union[sensor_msgs.msg.Image, numpy.ndarray], **_) sensor_msgs.msg.Image #
Takes a ROS Image message or numpy array and returns a ROS Image message
- Returns:
ROSImage
- classmethod get_ros_type() type #
- class ros_sugar.io.supported_types.CompressedImage#
Bases:
ros_sugar.io.supported_types.Image
CompressedImage format usually provided by camera vendors
- classmethod convert(output: Union[sensor_msgs.msg.CompressedImage, numpy.ndarray], **_) sensor_msgs.msg.CompressedImage #
Takes a ROS CompressedImage message or numpy array and returns a ROS CompressedImage message
- Returns:
ROSCompressedImage
- classmethod get_ros_type() type #
- class ros_sugar.io.supported_types.Audio#
Bases:
ros_sugar.io.supported_types.SupportedType
Audio.
- classmethod convert(output: Union[str, bytes], **_) std_msgs.msg.ByteMultiArray #
Takes an array of audio data and returns a ROS message of type AudioData
- Returns:
AudioData
- classmethod get_ros_type() type #
- class ros_sugar.io.supported_types.MapMetaData#
Bases:
ros_sugar.io.supported_types.SupportedType
MapMetaData.
- classmethod convert(output, **_) Any #
- classmethod get_ros_type() type #
- class ros_sugar.io.supported_types.Odometry#
Bases:
ros_sugar.io.supported_types.SupportedType
Odometry
- classmethod convert(output, **_) Any #
- classmethod get_ros_type() type #
- class ros_sugar.io.supported_types.LaserScan#
Bases:
ros_sugar.io.supported_types.SupportedType
LaserScan
- classmethod convert(output, **_) Any #
- classmethod get_ros_type() type #
- class ros_sugar.io.supported_types.Path#
Bases:
ros_sugar.io.supported_types.SupportedType
Path
- classmethod convert(output, **_) Any #
ROS message converter function for datatype
- Parameters:
args
- Return type:
Any
- classmethod get_ros_type() type #
- class ros_sugar.io.supported_types.OccupancyGrid#
Bases:
ros_sugar.io.supported_types.SupportedType
OccupancyGrid
- classmethod convert(output: numpy.ndarray, resolution: float, origin: Optional[geometry_msgs.msg.Pose] = None, msg_header: Optional[std_msgs.msg.Header] = None, **_) nav_msgs.msg.OccupancyGrid #
ROS message converter function for datatype OccupancyGrid.
- Parameters:
output (np.ndarray)
_
- Return type:
ROSOccupancyGrid
- classmethod get_ros_type() type #
- class ros_sugar.io.supported_types.Point#
Bases:
ros_sugar.io.supported_types.SupportedType
Point
- classmethod convert(output: numpy.ndarray, **_) geometry_msgs.msg.Point #
ROS message converter function for datatype Point.
- Parameters:
output (np.ndarray)
_
- Return type:
ROSPoint
- classmethod get_ros_type() type #
- class ros_sugar.io.supported_types.PointStamped#
Bases:
ros_sugar.io.supported_types.SupportedType
PointStamped
- classmethod convert(output: numpy.ndarray, frame_id=None, ros_time=None, **_) geometry_msgs.msg.PointStamped #
ROS message converter function for datatype Point.
- Parameters:
output (np.ndarray)
_
- Return type:
ROSPointStamped
- classmethod get_ros_type() type #
- class ros_sugar.io.supported_types.Pose#
Bases:
ros_sugar.io.supported_types.SupportedType
Pose
- classmethod convert(output: numpy.ndarray, frame_id=None, ros_time=None, **_) geometry_msgs.msg.Pose #
ROS message converter function for datatype Point.
- Parameters:
output (np.ndarray)
_
- Return type:
ROSPose
- classmethod get_ros_type() type #
- class ros_sugar.io.supported_types.PoseStamped#
Bases:
ros_sugar.io.supported_types.SupportedType
PoseStamped
- classmethod convert(output: numpy.ndarray, frame_id=None, ros_time=None, **_) geometry_msgs.msg.PoseStamped #
ROS message converter function for datatype Point.
- Parameters:
output (np.ndarray)
_
- Return type:
ROSPoseStamped
- classmethod get_ros_type() type #
- class ros_sugar.io.supported_types.ComponentStatus#
Bases:
ros_sugar.io.supported_types.SupportedType
Component Health Status
- classmethod convert(output, **_) Any #
- classmethod get_ros_type() type #
- class ros_sugar.io.supported_types.Twist#
Bases:
ros_sugar.io.supported_types.SupportedType
Twist for Control Commands
- classmethod convert(output, **_) Any #
- classmethod get_ros_type() type #