ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
I have never encounter this issue, but you should not publish within an interrupt handler.
It is generally a bad idea to do complex things (such as serialize and send through a serial port) during an interrupt (note that your millis()
counter will stop counting while you are in the handler so you should make it as short as possible).
You should set a flag in the interrupt and publish in your main loop if the flag is set.
Something like:
#include <ros.h>
#include <std_msgs/UInt64.h>
#include <CurieTimerOne.h>
ros::NodeHandle nh;
std_msgs::UInt64 msgs;
ros::Publisher unnamed_publisher("empty_topic", &msgs);
bool publish_flag = false;
void intFunc()
{
msgs.data = millis();
publish_flag = true;
}
void setup()
{
nh.initNode();
nh.advertise(unnamed_publisher);
// Interrupt 50 hz
int secToMicro = 1e6;
int Hz = 100;
CurieTimerOne.start(secToMicro / Hz, intFunc);
}
void loop()
{
if(publish_flag)
{
unnamed_publisher.publish(&msgs);
publish_flag = false;
}
nh.spinOnce();
delay(1); // optional
}