Project

General

Profile

Revision 49090532

ID490905327f0dbe5d2f11c8b765a5c832fada210a

Added by Thomas Mullins about 12 years ago

Tested rosserial a little with a 328.

It doesn't quite work yet. Writing works, reading has not been tested,
and rosserial acts weirdly inconsistent.

View differences:

scout_avr/src/main.cpp
1
#include "Atmega128rfa1.h"
1
#include "ros.h"
2 2
#include <std_msgs/UInt16.h>
3 3

  
4
/*int main()
4
ros::Publisher *ptest_out;
5

  
6
void callback(const std_msgs::UInt16& msg)
7
{
8
  ptest_out->publish(&msg);
9
}
10

  
11
int main()
5 12
{
6
  std_msgs::UInt16 counter;
7 13
  ros::NodeHandle nh;
8
  ros::Publisher test("rosserial_test", &counter);
14
  std_msgs::UInt16 msg;
15
  ros::Subscriber<std_msgs::UInt16> test_in("test_in", callback);
16
  ros::Publisher test_out("test_out", &msg);
17

  
18
  ptest_out = &test_out;
9 19

  
20
  msg.data = 0;
10 21
  nh.initNode();
11
  nh.advertise(test);
12
  counter.data = 0;
22
  nh.subscribe(test_in);
23
  nh.advertise(test_out);
13 24

  
14 25
  while (1)
15 26
  {
16
    test.publish(&counter);
17
    counter.data++;
18 27
    nh.spinOnce();
19 28
  }
20 29

  
21 30
  return 0;
22
}*/
31
}
23 32

  
24
extern "C"
33
/*extern "C"
25 34
{
26 35
#include <stdlib.h>
27 36
#include <string.h>
28 37
}
29 38

  
39
#include "Atmega128rfa1.h"
40

  
30 41
int main()
31 42
{
32 43
  char time[20];
33 44
  Atmega128rfa1 avr;
34 45
  avr.init();
46
  unsigned long now, next = 0;
35 47
  while (1)
36 48
  {
37
    ultoa(avr.time(), time, 10);
38
    avr.write((uint8_t*) time, strlen(time));
49
    now = avr.time();
50
    if (now > next) {
51
      next = now + 100;
52
      ultoa(avr.time(), time, 10);
53
      avr.write((uint8_t*) time, strlen(time));
54
      avr.write((uint8_t*) "\n\r", 1);
55
    }
39 56
  }
40 57
  return 0;
41
}
58
}*/
42 59

  

Also available in: Unified diff