-
Notifications
You must be signed in to change notification settings - Fork 15
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
feat(omron_node): diagnostics for frequency #14
Changes from 1 commit
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -26,6 +26,8 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI | |
|
||
#include <ros/ros.h> | ||
#include <boost/shared_ptr.hpp> | ||
#include <diagnostic_updater/diagnostic_updater.h> | ||
#include <diagnostic_updater/update_functions.h> | ||
#include <sensor_msgs/LaserScan.h> | ||
|
||
#include "odva_ethernetip/socket/tcp_socket.h" | ||
|
@@ -41,6 +43,8 @@ using eip::socket::TCPSocket; | |
using eip::socket::UDPSocket; | ||
using namespace omron_os32c_driver; | ||
|
||
double RATE = 12.856; | ||
|
||
int main(int argc, char *argv[]) | ||
{ | ||
ros::init(argc, argv, "os32c"); | ||
|
@@ -57,6 +61,12 @@ int main(int argc, char *argv[]) | |
// publisher for laserscans | ||
ros::Publisher laserscan_pub = nh.advertise<LaserScan>("scan", 1); | ||
|
||
// diagnostics for frequency, monitor with 0.1 tolerance | ||
diagnostic_updater::Updater updater; | ||
updater.setHardwareID(host); | ||
diagnostic_updater::FrequencyStatus frequency_status(diagnostic_updater::FrequencyStatusParam(&RATE, &RATE)); | ||
updater.add(frequency_status); | ||
|
||
boost::asio::io_service io_service; | ||
shared_ptr<TCPSocket> socket = shared_ptr<TCPSocket>(new TCPSocket(io_service)); | ||
shared_ptr<UDPSocket> io_socket = shared_ptr<UDPSocket>(new UDPSocket(io_service, 2222)); | ||
|
@@ -113,6 +123,10 @@ int main(int argc, char *argv[]) | |
laserscan_msg.header.seq++; | ||
laserscan_pub.publish(laserscan_msg); | ||
|
||
// Tick the frequency and update the diagnostics | ||
frequency_status.tick(); | ||
updater.update(); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Any reason to do this separately vs. using DiagnosedPublisher? http://docs.ros.org/api/diagnostic_updater/html/classdiagnostic__updater_1_1DiagnosedPublisher.html There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Thanks for the review, I was not aware of the |
||
|
||
// Every tenth message received, send the keepalive message in response. | ||
// TODO: Make this time-based instead of message-count based. | ||
if (++ctr > 10) | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Parameterize the expected rate and permitted deviation, please.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Ok, any suggestions for naming?
~expected_frequency
(default=12.856
)~frequency_tolerance
(default=0.1
)~timestamp_min_acceptable
(default=-1
)~timestamp_max_acceptable
(default=5
)