Class Node
Defined in File node.hpp
Inheritance Relationships
Base Type
public rclcpp::Node
Class Documentation
-
class Node : public rclcpp::Node
ROS Node for gazebo plugins.
Wrapper around an rclcpp::Node which ensures all instances share an executor.
Public Types
Shared pointer to a gazebo_ros::Node.
Public Functions
-
virtual ~Node()
Destructor.
Public Static Functions
-
static SharedPtr Get()
Get a static node called “gazebo” which can be shared by several plugins.
This will call rclcpp::init if it hasn’t been called yet.
The node is created the first time this is called.
- Returns:
A shared pointer to a gazebo_ros::Node
-
static SharedPtr Get(sdf::ElementPtr _sdf, std::string _node_name = "")
Get reference to a gazebo_ros::Node and add it to the global gazebo_ros::Executor.
This will create a new node; the node’s name will be the same as the name argument on the <plugin> tag.
This will call rclcpp::init if it hasn’t been called yet.
Sets node name, namespace, remappings, parameters, and quality of service from SDF. SDF is in the form:
<!-- Node name will be the same as the plugin name --> <plugin name="my_node_name" filename="my_library.so"> <!-- Optional configurations for a plugin's Node --> <ros> <!-- Namespace of the node --> <namespace>/my_ns</namespace> <!-- Command line arguments sent to Node's constructor for remappings --> <argument>__name:=super_cool_node</argument> <argument>__log_level:=debug</argument> <!-- Initial ROS params set for node --> <parameter name="max_velocity" type="int">55</parameter> <parameter name="publish_odom" type="bool">True</parameter> <!-- Remapping rules for node --> <remapping>my_topic:=new_topic</remapping> <!-- QoS for node publishers and subscriptions --> <qos> <!-- See #gazebo_ros::QoS --> </qos> </ros> </plugin>
- Parameters:
_sdf – [in] An SDF element in the style above or containing a <ros> tag in the style above
_node_name – [in] An optional node_name to overwrite plugin name being used as node name.
- Returns:
A shared pointer to a new gazebo_ros::Node. A nullptr is returned and an error message is logged in case multiple nodes have the same name.
Create a gazebo_ros::Node and add it to the global gazebo_ros::Executor.
This will call rclcpp::init if it hasn’t been called yet.
Forwards arguments to the constructor for rclcpp::Node
- Parameters:
args – [in] List of arguments to pass to rclcpp::Node
- Returns:
A shared pointer to a new gazebo_ros::Node
-
static rclcpp::Parameter sdf_to_ros_parameter(sdf::ElementPtr const &_sdf)
Convert an sdf element to an rclcpp::Parameter.