Ros2Factory#
Fully qualified name: isaacsim::ros2::bridge::Ros2Factory
-
class Ros2Factory#
Base class for creating ROS 2 related functions/objects according to the sourced ROS 2 distribution.
Public Functions
-
virtual ~Ros2Factory() = default#
Destructor.
-
virtual std::shared_ptr<Ros2ContextHandle> createContextHandle() = 0#
Create a ROS 2 context handler.
- Returns:
Pointer to the context handler.
- virtual std::shared_ptr<Ros2NodeHandle> createNodeHandle(
- const char *name,
- const char *namespaceName,
- Ros2ContextHandle *contextHandle,
Create a ROS 2 node handler.
- Parameters:
name – Name of the node.
namespaceName – Namespace of the node.
contextHandle – Context handler.
- Returns:
Pointer to the node handler.
- virtual std::shared_ptr<Ros2Publisher> createPublisher(
- Ros2NodeHandle *nodeHandle,
- const char *topicName,
- const void *typeSupport,
- const Ros2QoSProfile &qos,
Create a ROS 2 publisher.
- Parameters:
nodeHandle – Node handler.
topicName – Name of the topic to publish on.
typeSupport – Message type support.
qos – Quality of service profile.
- Returns:
Pointer to the publisher.
- virtual std::shared_ptr<Ros2Subscriber> createSubscriber(
- Ros2NodeHandle *nodeHandle,
- const char *topicName,
- const void *typeSupport,
- const Ros2QoSProfile &qos,
Create a ROS 2 subscriber.
- Parameters:
nodeHandle – Node handler.
topicName – Name of the topic to subscribe to.
typeSupport – Message type support.
qos – Quality of Service profile.
- Returns:
Pointer to the subscriber.
- virtual std::shared_ptr<Ros2Service> createService(
- Ros2NodeHandle *nodeHandle,
- const char *serviceName,
- const void *typeSupport,
- const Ros2QoSProfile &qos,
Create a ROS 2 service server.
- Parameters:
nodeHandle – Node handler.
serviceName – Name of the service.
typeSupport – Message type support.
qos – Quality of Service profile.
- Returns:
Pointer to the service server.
- virtual std::shared_ptr<Ros2Client> createClient(
- Ros2NodeHandle *nodeHandle,
- const char *serviceName,
- const void *typeSupport,
- const Ros2QoSProfile &qos,
Create a ROS 2 service client.
- Parameters:
nodeHandle – Node handler.
serviceName – Name of the service.
typeSupport – Message type support.
qos – Quality of Service profile.
- Returns:
Pointer to the service client.
-
virtual std::shared_ptr<Ros2ClockMessage> createClockMessage() = 0#
Create a ROS 2
rosgraph_msgs/msg/Clock
message.- Returns:
Pointer to the message.
-
virtual std::shared_ptr<Ros2ImuMessage> createImuMessage() = 0#
Create a ROS 2
sensor_msgs/msg/Imu
message.- Returns:
Pointer to the message.
- virtual std::shared_ptr<Ros2CameraInfoMessage> createCameraInfoMessage(
Create a ROS 2
sensor_msgs/msg/CameraInfo
message.- Returns:
Pointer to the message.
-
virtual std::shared_ptr<Ros2ImageMessage> createImageMessage() = 0#
Create a ROS 2
sensor_msgs/msg/Image
message.- Returns:
Pointer to the message.
- virtual std::shared_ptr<Ros2NitrosBridgeImageMessage> createNitrosBridgeImageMessage(
Create a ROS 2
isaac_ros_nitros_bridge_interfaces/msg/NitrosBridgeImage
message.- Returns:
Pointer to the message.
- virtual std::shared_ptr<Ros2BoundingBox2DMessage> createBoundingBox2DMessage(
Create a ROS 2
vision_msgs/msg/Detection2DArray
message.- Returns:
Pointer to the message.
- virtual std::shared_ptr<Ros2BoundingBox3DMessage> createBoundingBox3DMessage(
Create a ROS 2
vision_msgs/msg/Detection3DArray
message.- Returns:
Pointer to the message.
- virtual std::shared_ptr<Ros2OdometryMessage> createOdometryMessage(
Create a ROS 2
nav_msgs/msg/Odometry
message.- Returns:
Pointer to the message.
- virtual std::shared_ptr<Ros2RawTfTreeMessage> createRawTfTreeMessage(
Create a ROS 2
tf2_msgs/msg/TFMessage
message.- Returns:
Pointer to the message.
- virtual std::shared_ptr<Ros2SemanticLabelMessage> createSemanticLabelMessage(
Create a ROS 2
std_msgs/msg/String
message as semantic label.- Returns:
Pointer to the message.
- virtual std::shared_ptr<Ros2JointStateMessage> createJointStateMessage(
Create a ROS 2
sensor_msgs/msg/JointState
message.- Returns:
Pointer to the message.
- virtual std::shared_ptr<Ros2PointCloudMessage> createPointCloudMessage(
Create a ROS 2
sensor_msgs/msg/PointCloud2
message.- Returns:
Pointer to the message.
- virtual std::shared_ptr<Ros2LaserScanMessage> createLaserScanMessage(
Create a ROS 2
sensor_msgs/msg/LaserScan
message.- Returns:
Pointer to the message.
-
virtual std::shared_ptr<Ros2TfTreeMessage> createTfTreeMessage() = 0#
Create a ROS 2
tf2_msgs/msg/TFMessage
message.- Returns:
Pointer to the message.
-
virtual std::shared_ptr<Ros2TwistMessage> createTwistMessage() = 0#
Create a ROS 2
geometry_msgs/msg/Twist
message.- Returns:
Pointer to the message.
- virtual std::shared_ptr<Ros2AckermannDriveStampedMessage> createAckermannDriveStampedMessage(
Create a ROS 2
ackermann_msgs/msg/AckermannDriveStamped
message.- Returns:
Pointer to the message.
- virtual std::shared_ptr<Ros2Message> createDynamicMessage(
- const std::string &pkgName,
- const std::string &msgSubfolder,
- const std::string &msgName,
- BackendMessageType messageType = BackendMessageType::eMessage,
Create a ROS 2 dynamic message.
- Parameters:
pkgName – Message package name (e.g.:
"std_msgs"
forstd_msgs/msg/Int32
).msgSubfolder – Message subfolder name (e.g.:
"msg"
forstd_msgs/msg/Int32
).msgName – Message name (e.g.:
"Int32"
forstd_msgs/msg/Int32
).messageType – Message type.
- Returns:
Pointer to the dynamic message.
-
virtual bool validateTopicName(const std::string &topicName) = 0#
Determine if the given topic name is valid.
- Parameters:
topicName – Topic name.
- Returns:
Whether the topic name is valid.
- virtual bool validateNamespaceName(
- const std::string &namespaceName,
Determine if the given node namespace name is valid.
- Parameters:
namespaceName – Namespace name.
- Returns:
Whether the node namespace name is valid.
-
virtual bool validateNodeName(const std::string &nodeName) = 0#
Determine if the given node name is valid.
- Parameters:
nodeName – Node name.
- Returns:
Whether the node name is valid.
-
virtual ~Ros2Factory() = default#