Class NodeWithOptionalMaster

Inheritance Relationships

Base Type

  • public cras::HasLogger

Class Documentation

class NodeWithOptionalMaster : public cras::HasLogger

Node that can run both with and without a ROS master. This can be useful for one-off scripts that do not need to publish or subscribe anything, but they want to make use of the parameter processing and name remapping.

This class provides an interface similar to ros::NodeHandle. However, when init() is called, it first checks whether the rosmaster is running and can be contacted. If not, this class falls back to a mode with no master. It will still provide parameters and name resolving, however, only for the parameters and remaps directly specified when launching the node. When running without master, simulation time is never used.

Public Functions

explicit NodeWithOptionalMaster(const ::cras::LogHelperPtr &log)
Parameters:

log[in] Logger.

virtual ~NodeWithOptionalMaster()
void init(const ::ros::M_string &remappings, const ::std::string &name, uint32_t options)

Initialize the node, autodetecting whether a ros master is running or not.

Parameters:
  • remappings[in] Remappings of parameters and topics.

  • name[in] Node name.

  • options[in] Node init options.

void init(int &argc, char **argv, const ::std::string &name, uint32_t options)

Initialize the node, autodetecting whether a ros master is running or not.

Parameters:
  • argc[in] Nr. of CLI args.

  • argv[in] CLI args.

  • name[in] Node name.

  • options[in] Node init options.

void init(const ::ros::VP_string &remappings, const ::std::string &name, uint32_t options)

Initialize the node, autodetecting whether a ros master is running or not.

Parameters:
  • remappings[in] Remappings of parameters and topics.

  • name[in] Node name.

  • options[in] Node init options.

void shutdown()

Shutdown the node.

bool isInitialized() const

Has init() been called?

bool usesMaster() const

Is a live ROS master being used?

bool ok() const

Equivalent of ros::ok() .

::std::string resolveName(const ::std::string &name, bool remap = true) const

Resolve a name relative to the global namespace.

Parameters:
  • name – The name to be resolved (cannot start with ~).

  • remap – Whether remapping should be applied.

Returns:

The resolved name.

::cras::BoundParamHelperPtr getPrivateParams() const

Get private parameters of the node.

Remark

When running without master, only parameters directly specified in remappings will be available.

Returns:

The parameters object.