Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[Arduino] Add an example to use Subscriber and ServiceServer in a class #321

Merged
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
#include <ros.h>
#include <std_srvs/SetBool.h>
#include <std_msgs/UInt16.h>

ros::NodeHandle nh;

class Blinker
{
public:
Blinker(byte pin, uint16_t period)
: pin_(pin), period_(period),
subscriber_("set_blink_period", &Blinker::set_period_callback, this),
service_server_("activate_blinker", &Blinker::service_callback, this)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Might be slightly clearer to have these members as pointers and then initialize the objects in the constructor, but I'm not married to having it that way.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You mean, I should do dynamic memory allocation on a microcontroller? I am not a fan of that...

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It's a one-time allocation at startup, so that's pretty safe, but if you'd rather not, it can stay as-is. Another possibility would be adding do-nothing constructors to the classes so that they can be initialized empty and the reinitialized afterward.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I prefer the do-nothing constructor path. But I don't get why you want to initialize the class later? In the setup()
function to avoid the init() method?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

All I'm suggesting is having the option for the example to look like this, which feels a bit more like idiomatic roscpp:

  Blinker(byte pin, uint16_t period) : pin_(pin), period_(period)
  {
    subscriber_ = ros::Subscriber("set_blink_period", &Blinker::set_period_callback, this),
    service_server_ = ros::ServiceServer("activate_blinker", &Blinker::service_callback, this)
  }

  void init(ros::NodeHandle& nh)
  {
    pinMode(pin_, OUTPUT);

    nh.subscribe(subscriber_);
    nh.advertiseService(service_server_);
  }

However, it's not going to work regardless without also re-specifying all the template arguments since there's no type inference on constructors, so that kind of blows it away anyway (and there'd need to be copy constructors added). So I think the best thing is to merge this contribution as-is, and if there's interest now or later in streamlining or adding to the API, that can be discussed on separate PR.

{}

void init(ros::NodeHandle& nh)
{
pinMode(pin_, OUTPUT);
nh.subscribe(subscriber_);
nh.advertiseService(service_server_);
}

void run()
{
if(active_ && ((millis() - last_time_) >= period_))
{
last_time_ = millis();
digitalWrite(pin_, !digitalRead(pin_));
}
}

void set_period_callback(const std_msgs::UInt16& msg)
{
period_ = msg.data;
}

void service_callback(const std_srvs::SetBool::Request& req,
std_srvs::SetBool::Response& res)
{
active_ = req.data;
res.success = true;
if(req.data)
res.message = "Blinker ON";
else
res.message = "Blinker OFF";
}

private:
const byte pin_;
bool active_ = true;
uint16_t period_;
uint32_t last_time_;
ros::Subscriber<std_msgs::UInt16, Blinker> subscriber_;
ros::ServiceServer<std_srvs::SetBool::Request, std_srvs::SetBool::Response, Blinker> service_server_;
};

Blinker blinker(LED_BUILTIN, 500);

void setup()
{
nh.initNode();
blinker.init(nh);
}

void loop()
{
blinker.run();
nh.spinOnce();
delay(1);
}