VEXProRangePublish.cpp
Go to the documentation of this file.
1 /*
2  * VEXProRangePublish.cpp
3  *
4  * Created on: Jul 12, 2012
5  * Author: bouchier
6  *
7  * Publish the range from an ultrasonic ranging sensor connected to digital 1 (Input) &
8  * digital 2 (Output) on topic sonar1
9  */
10 
11 #include <ros.h>
12 #include <std_msgs/Int32.h>
13 #include <stdio.h>
14 #include <unistd.h>
15 #include "qegpioint.h"
16 
18 std_msgs::Int32 range;
19 ros::Publisher sonar1("sonar1", &range);
20 
21 char *rosSrvrIp = "192.168.11.9";
22 
23 #define USPI 150
24 #define BIAS 300
25 
26 unsigned long diff(struct timeval *ptv0, struct timeval *ptv1)
27 {
28  long val;
29 
30  val = ptv1->tv_usec - ptv0->tv_usec;
31  val += (ptv1->tv_sec - ptv0->tv_sec)*1000000;
32 
33  return val;
34 }
35 
36 void callback(unsigned int io, struct timeval *ptv, void *userdata)
37 {
38  static struct timeval tv0;
39  static int flag = 0;
40  int sonarVal;
41 
42  if (io==0)
43  {
44  flag = 1;
45  tv0 = *ptv;
46  }
47 
48  if (io==1 && flag)
49  {
50  sonarVal = diff(&tv0, ptv);
51  if (sonarVal>BIAS)
52  sonarVal = (sonarVal-BIAS)/USPI;
53  range.data = sonarVal;
54  printf("%d\n", sonarVal);
55  }
56 }
57 
58 // Note: connector labeled "INPUT" on sonar sensor goes to
59 // digital 1 (bit 0), and connector labeled "OUTPUT" goes to
60 // digital 2 (bit 1).
61 int main()
62 {
63  CQEGpioInt &gpio = CQEGpioInt::GetRef();
64  volatile unsigned int d;
65 
66  // reset bit 0, set as output for sonar trigger
67  gpio.SetData(0x0000);
68  gpio.SetDataDirection(0x0001);
69 
70  // set callbacks on negative edge for both bits 0 (trigger)
71  // and 1 (echo)
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);
76 
77  //nh.initNode();
78  nh.initNode(rosSrvrIp);
79  nh.advertise(sonar1);
80 
81  // trigger sonar by toggling bit 0
82  while(1)
83  {
84  gpio.SetData(0x0001);
85  for (d=0; d<120000; d++);
86  gpio.SetData(0x0000);
87  sleep(1); // the interrupt breaks us out of this sleep
88  sleep(1); // now really sleep a second
89  sonar1.publish( &range );
90  nh.spinOnce();
91  }
92 }
93 
94 
ros::NodeHandle nh
d
void publish(const boost::shared_ptr< M > &message) const
#define USPI
void callback(unsigned int io, struct timeval *ptv, void *userdata)
#define BIAS
char * rosSrvrIp
CQEGpioInt & gpio
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
unsigned long diff(struct timeval *ptv0, struct timeval *ptv1)
std_msgs::Int32 range
int main()
ros::Publisher sonar1("sonar1",&range)


rosserial_embeddedlinux
Author(s): Paul Bouchier
autogenerated on Mon Jun 10 2019 14:53:23