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/Makefile
1
MCU=atmega128rfa1
2
F_CPU=16000000
1
#MCU=atmega128rfa1
2
MCU=atmega328
3
F_CPU=8000000
3 4
SRC=src/*.cpp src/ros_lib/*.cpp
4 5
FLAGS=-Isrc/ros_lib -Isrc -mmcu=$(MCU) -DF_CPU=$(F_CPU)UL -funsigned-char -Os -fpack-struct -Wall
5 6

  
......
11 12
scout_avr.elf: $(SRC)
12 13
	avr-g++ $(FLAGS) $(SRC) -o scout_avr.elf
13 14

  
15
download: scout_avr.hex
16
	avrdude -p m328p -c avrispMKII -P usb -F -U flash:w:scout_avr.hex
17

  
14 18
clean:
15 19
	rm -f scout_avr.elf scout_avr.hex
scout_avr/launch/rosserial.launch
1
<launch>
2
  <node pkg="rosserial_python" type="serial_node.py" name="serial_node">
3
    <param name="~port" value="/dev/ttyUSB0" />
4
    <param name="~baud" value="38400" />
5
  </node>
6
</launch>
scout_avr/src/Atmega128rfa1.cpp
4 4
{
5 5
#include <avr/io.h>
6 6
#include <avr/interrupt.h>
7
  void __cxa_pure_virtual(void) {}
7 8
}
8 9

  
9 10
unsigned long millis;
......
20 21
  millis++;
21 22
}
22 23

  
23
ISR(USART0_RX_vect)
24
ISR(USART_RX_vect)
24 25
{
25 26
  char data = UDR0;
26 27
  if (rx_start == rx_end-1 || (rx_start == RX_BUFFER_SIZE-1 && rx_end == 0))
......
39 40
void Atmega128rfa1::init()
40 41
{
41 42
  // === init serial ===
42
  // for 16 MHz clock, 76800 baud
43
  uint16_t baud = 12;
44
  UBRR0H = baud >> 8;
45
  UBRR0L = baud;
43
  // baud = F_CPU / (16 (UBRR + 1))
44
  uint16_t ubrr = F_CPU / 16 / 38400 - 1;
45
  UBRR0H = ubrr >> 8;
46
  UBRR0L = ubrr;
46 47
  // UMSEL0 = 0, asynchronous usart
47 48
  // UPM0 = 0, parity check disabled
48 49
  // USBS0 = 0, 1 stop bit
......
59 60
  // enable interrupt on compare match A
60 61
  TIMSK0 = _BV(OCIE0A);
61 62
  // (1 ms) * 16 MHz / 64 prescaler = 250
62
  OCR0A = 250;
63
  //OCR0A = 250;
64
  // (1 ms) * 8 MHz / 64 prescaler = 125
65
  OCR0A = 125;
63 66
  millis = 0;
64 67

  
65 68
  sei();
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

  
scout_avr/src/ros_lib/ros/node_handle.h
386 386
          return l;
387 387
        }else{
388 388
          logerror("Message from device dropped: message larger than buffer.");
389
          return 0;
389 390
        }
390 391
      }
391 392

  

Also available in: Unified diff