12 #include <std_msgs/Int32.h> 15 #include "qegpioint.h" 26 unsigned long diff(
struct timeval *ptv0,
struct timeval *ptv1)
30 val = ptv1->tv_usec - ptv0->tv_usec;
31 val += (ptv1->tv_sec - ptv0->tv_sec)*1000000;
36 void callback(
unsigned int io,
struct timeval *ptv,
void *userdata)
38 static struct timeval tv0;
50 sonarVal =
diff(&tv0, ptv);
53 range.data = sonarVal;
54 printf(
"%d\n", sonarVal);
63 CQEGpioInt &
gpio = CQEGpioInt::GetRef();
64 volatile unsigned int d;
68 gpio.SetDataDirection(0x0001);
72 gpio.RegisterCallback(0, NULL,
callback);
73 gpio.RegisterCallback(1, NULL,
callback);
74 gpio.SetInterruptMode(0, QEG_INTERRUPT_NEGEDGE);
75 gpio.SetInterruptMode(1, QEG_INTERRUPT_NEGEDGE);
85 for (d=0; d<120000; d++);
void publish(const boost::shared_ptr< M > &message) const
void callback(unsigned int io, struct timeval *ptv, void *userdata)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
unsigned long diff(struct timeval *ptv0, struct timeval *ptv1)
ros::Publisher sonar1("sonar1",&range)