ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

The problem is likely this:

class BlobDetectNodelet : public nodelet::Nodelet {
 public:
  BlobDetectNodelet(const std::string& cameraName) : nodelet::Nodelet(){}
  ...

With a nodelet, the constructor of your class is not allowed to have any arguments.

Think about it: nodelets are loaded as plugins, and the loader / registration code (ie: PLUGINLIB_EXPORT_CLASS(..)) is generic (ie: it must be able to load all subclasses of nodelet::Nodelet, not just yours). How would the generic loader code "know" what arguments to supply for your specific subclass?

The compiler error is pretty clear about it (clear as in: it tells you what the problem it encounters is, not what the root cause is):

/opt/ros/noetic/include/class_loader/meta_object.hpp:198:12: error: no matching function for call to ‘blob_detect::BlobDetectNodelet::BlobDetectNodelet()’
  198 |     return new C;
      |            ^~~~~

this basically says: "I tried instantiating BlobDetectNodelet using a zero-argument ctor, as I am instructed to do by the code underlying PLUGINLIB_EXPORT_CLASS(..), but there is no such ctor, so I'm giving up".

The idea for nodelets is to read in their "ROS parameters" (and do everything else needed to initialise the nodelet) when the nodelet::onInit(..) method is called. If you need a "camera name" parameter, that would be the place to retrieve it from the parameter server.

I would expect things to work if you remove the const std::string& cameraName argument from the ctor.

The problem is likely this:

class BlobDetectNodelet : public nodelet::Nodelet {
 public:
  BlobDetectNodelet(const std::string& cameraName) : nodelet::Nodelet(){}
  ...

With a nodelet, the constructor of your class is not allowed to have any arguments.

Think about it: nodelets are loaded as plugins, and the loader / registration code (ie: PLUGINLIB_EXPORT_CLASS(..)) is generic (ie: it must be able to load all subclasses of nodelet::Nodelet, not just yours). How would the generic loader code "know" what arguments to supply for your specific subclass?

The compiler error is pretty clear about it (clear as in: it tells you what the problem it encounters is, not what the root cause is):

/opt/ros/noetic/include/class_loader/meta_object.hpp:198:12: error: no matching function for call to ‘blob_detect::BlobDetectNodelet::BlobDetectNodelet()’
  198 |     return new C;
      |            ^~~~~

this basically says: "I tried instantiating BlobDetectNodelet using a zero-argument ctor, as I am instructed to do by the code underlying PLUGINLIB_EXPORT_CLASS(..), but there is no such ctor, so I'm giving up".

The idea for nodelets is to read in their "ROS parameters" (and do everything else needed to initialise the nodelet) when the nodelet::onInit(..) method is called. If you need a "camera name" parameter, that onInit(..) would be the place to retrieve it from the parameter server.

I would expect things to work if you remove the const std::string& cameraName argument from the ctor.