Go to the documentation of this file.00001 #include "ros/ros.h"
00002 #include "openreroc_motion_sensor.h"
00003 #include <stdio.h>
00004 #include <unistd.h>
00005 #include <stdlib.h>
00006 #include <sys/types.h>
00007 #include <sys/stat.h>
00008 #include <fcntl.h>
00009
00010 int main(int argc, char **argv)
00011 {
00012 int fd_32;
00013 int rc;
00014 unsigned int buf;
00015 fd_32 = open("/dev/xillybus_read_32", O_RDONLY);
00016 ros::init(argc, argv, "openreroc_motion_sensor");
00017 ros::NodeHandle n;
00018 ros::Publisher pub_openreroc_motion_sensor = n.advertise<openreroc_motion_sensor::openreroc_motion_sensor>("openreroc_motion_sensor", 1000);
00019 ros::Rate loop_rate(10);
00020 openreroc_motion_sensor::openreroc_motion_sensor msg;
00021 int cur=0;
00022 while (ros::ok())
00023 {
00024 rc = read(fd_32, &buf, sizeof(buf));
00025 if(cur != buf && buf != 1){
00026 msg.sensor_data = buf;
00027
00028 }
00029 cur = buf;
00030 pub_openreroc_motion_sensor.publish(msg);
00031 ros::spinOnce();
00032
00033 }
00034
00035 close(fd_32);
00036 return 0;
00037 }