Views
URM37 V3.2 Ultrasonic Sensor (SKU:SEN0001)
From Robot Wiki
Contents |
Introduction
URM37 V3.2 Ultrasonic Sensor uses an industrial level AVR processor as the main processing unit. It comes with a temperature correction which is very unique in its class.
Specification
- Power: +5V
- Current: <20mA
- Working temperature: -10℃~+70℃
- Detecting range: 4cm-5m
- Resolution: 1cm
- Interface: RS232 (TTL), PWM
- Servo control: One servo control output
- Operating Mode: Serial; (PWM) passive control mode; Autonomous Mode; On/OFF Mode
- Temperature sensor: 12 bits reading from serial port
- Size: 22mm × 51 mm
- Weight: 30g
1. +VCC - +5V Power
2. GND - Ground
3. RST - Reset
4. PWM - PWM Output 0-25000US,Every 50US represent 1cm
5. MOTO - Servo control signal output
6. COMP/TRIG
- COMP - On/OFF mode, when the detecting distance is smaller than a pre-set value, this pin pulls low.
- TRIG - PWM or RS232 trigger pin
- COMP - On/OFF mode, when the detecting distance is smaller than a pre-set value, this pin pulls low.
7. NC
8. RXD - RS232,TTL communication
9. TXD - RS232,TTL communication
Compare with other ultrasonic sensor
Compare with SRF08 and XL-MaxSonar-WRC1 Ultrasonic Distance Sensor Evaluating
Hardware requierments
- 1×URM37 V3.2 Ultrasonic Sensor
- 1×Arduino Microcontroller
- 1×IO Expansion Shield For Arduino(V5)
- 1×USB cable
Tools used
- 4×jumper wire
Software
- Arduino IDE
Working Mode Selection
The working mode can be changed by writing 0x00, 0x01 or 0x02 to EEPROM through serial port.
Mode 1: Serial passive control mode
Under this mode, the sensor is always waiting for command from serial port. Every time it receives a command, it will return the distance and wait for the next command. The degree in the command will be used to control a servo motor to rotate corresponding degree. Please note that this mode is always on. It can not be switch on or off.
Jumper setting for RS232 and TTL output
The selection of RS232 or TTL output level is switched by changing three jumpers (J1, J2, J3). A diagram below illustrates the setting:
Warning: Do not connect to TTL MCU when the output mode is set to RS232, doing so will permanently damage the unit.
This feature is only available for Rev2 and after. If there are no jumpers on the back of the sensor, the sensor is Rev1 and hence not supporting this feature.
Mode 2: Autonomous trigger mode
Under this mode, the sensor will make a sensor reading every 25ms and compare the reading with a threshold (pre-set, user is able to define this value by writing EEPROM), if the reading is equal or smaller than the threshold, pin COMP/TRIG will have low output. In the meantime, pin PWM will output the distance reading, every 50us low level stands for 1cm, by counting the number of these pulses, the distance can be calculated. This mode can be simply used as an ON/OFF switch.
Mode 3: PWM passive control mode
Under this mode, a low pull on pin COMP/TRIG will trigger a sensor reading. The width of the pulse is proportional to the servo rotating degree. After a successful sensor reading, Pin PWM will output pulses, every 50us represents 1cm. If the reading is invalid, a 50000us pulse will be returned.
The sketch for PWM passive control mode
// # Editor :Jiang from DFRobot
// # Data :18.09.2012
// # Product name:ultrasonic scanner
// # Product SKU:SEN0001
// # Version : 0.2
// # Description:
// # The Sketch for scanning 180 degree area 4-500cm detecting range
// # Connection:
// # Pin 1 VCC (URM V3.2) -> VCC (Arduino)
// # Pin 2 GND (URM V3.2) -> GND (Arduino)
// # Pin 4 PWM (URM V3.2) -> Pin 3 (Arduino)
// # Pin 6 COMP/TRIG (URM V3.2) -> Pin 5 (Arduino)
// #
int URPWM = 3; // PWM Output 0-25000US,Every 50US represent 1cm
int URTRIG=5; // PWM trigger pin
unsigned int Distance=0;
uint8_t EnPwmCmd[4]={0x44,0x02,0xbb,0x01}; // distance measure command
void setup(){ // Serial initialization
Serial.begin(9600); // Sets the baud rate to 9600
PWM_Mode_Setup();
}
void loop()
{
PWM_Mode();
delay(20);
} //PWM mode setup function
void PWM_Mode_Setup(){
pinMode(URTRIG,OUTPUT); // A low pull on pin COMP/TRIG
digitalWrite(URTRIG,HIGH); // Set to HIGH
pinMode(URPWM, INPUT); // Sending Enable PWM mode command
for(int i=0;i<4;i++){
Serial.write(EnPwmCmd[i]);
}
}
void PWM_Mode(){ // a low pull on pin COMP/TRIG triggering a sensor reading
digitalWrite(URTRIG, LOW);
digitalWrite(URTRIG, HIGH); // reading Pin PWM will output pulses
unsigned long DistanceMeasured=pulseIn(URPWM,LOW);
if(DistanceMeasured==50000){ // the reading is invalid.
Serial.print("Invalid");
}
else{
Distance=DistanceMeasured/50; // every 50us low level stands for 1cm
}
Serial.print("Distance=");
Serial.print(Distance);
Serial.println("cm");
}
Serial control protocol
Serial setting:Port rate: 9600; Parity: none; Stop bit: 1
Command: Control command consists of four bits, command+data0+data1+sum. Sum=Low 8 bit of the sum of command+data0+data1.
| Command Format | Function | Description |
|---|---|---|
| 0x11+NC+NC+Sum (Sample: 0x11 0x00 0x00 0x11) | Enable 16 bit temperature reading | Reading the temperature, the return data format will be:
0x11+High(temperature)+Low(temperature)+SUM
|
| 0x22+Degree+NC+SUM (Sample: 0x22 0x00 0x00 0x22 ) | Enable 16 bit distance reading | The degree in the command is used to control a servo motor to rotate corresponding degree.
|
| 0x33+Add+NC+SUM | Enable internal EEPROM reading | Return data will be 0x33+Add+Data+SUM. |
| 0x44+Add+Data+SUM (Sample: 0x44 0x02 0xbb 0x01) Enable PWM mode | Enable internal EEPROM writing | Written data can only from 0-255.
Address 0x00-0x02 is used to configure the mode.
0x00 – threshold distance (Low)
0x01 – threshold distance (High)
0x02 – Operation Mode
(0xaa for autonomous mode)
(0xbb for PWM passive control mode)
|
Note:NC stands for any data,SUM stands for sum, Add stands for address.
1. PWN_ON must be set to High to enable sensor.
Examples: Function to calculate the temperature:
IF(HightByte>=0xF0)
{
Temperature= ((HightByte-0xF0)*256-LowByte)/10
}
Else
{
Temperature= ((HightByte)*256-LowByte)/10
}
Servo control command reference table:
| DEC | 0 | 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 |
| HEX | 0 | 01 | 02 | 03 | 04 | 05 | 06 | 07 | 08 | 09 | 0A | 0B | 0C | 0D | 0E | 0F |
| Degree | 0 | 6 | 12 | 18 | 24 | 29 | 35 | 41 | 47 | 53 | 59 | 65 | 70 | 76 | 82 | 88 |
| DEC | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 |
| HEX | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 1A | 1B | 1C | 1D | 1E | 1F |
| Degree | 94 | 100 | 106 | 112 | 117 | 123 | 129 | 135 | 141 | 147 | 153 | 159 | 164 | 170 | 176 | 182 |
| DEC | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | |
| HEX | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 2A | 2B | 2C | 2D | 2E | |
| Degree | 188 | 194 | 200 | 206 | 211 | 217 | 223 | 229 | 235 | 241 | 247 | 252 | 258 | 264 | 270 |
V3.2 Help Mate Download:
Help Mate
Arduino Sketch
Use a servo to control the position,and the ultrasonic sensor to judge the distance.Here is the sketch.
NOTE: Please put the sensor jumpers to TTL mode. See above for a picture indicating TTL mode
// # Editor : Jiang from DFRobot
// # Data : 24.07.2012
// # Product name:ultrasonic scanner Kit
// # Product SKU:SEN0001
// # Version : 0.2
// # Description:
// # The Sketch for scanning 180 degree area 4-500cm detecting range
// # Connection:
// # Pin 1 VCC (URM V3.2) -> VCC (Arduino)
// # Pin 2 GND (URM V3.2) -> GND (Arduino)
// # Pin 4 PWM (URM V3.2) -> Pin 3 (Arduino)
// # Pin 6 COMP/TRIG (URM V3.2) -> Pin 5 (Arduino)
// # Pin mode: PWM
// # Working Mode: PWM passive control mode.
// # If it is your first time to use it,please make sure the two jumpers to the right hand
// # side of the device are set to TTL mode. You'll also find a secondary jumper on
// # the left hand side, you must break this connection or you may damage your device.
#include <Servo.h> // Include Servo library
Servo myservo; // create servo object to control a servo
int pos=0; // variable to store the servo position
int URPWM=3; // PWM Output 0-25000us,every 50us represent 1cm
int URTRIG=5; // PWM trigger pin
boolean up=true; // create a boolean variable
unsigned long time; // create a time variable
unsigned long urmTimer = 0; // timer for managing the sensor reading flash rate
unsigned int Distance=0;
uint8_t EnPwmCmd[4]={0x44,0x22,0xbb,0x01}; // distance measure command
void setup(){ // Serial initialization
Serial.begin(9600); // Sets the baud rate to 9600
myservo.attach(9); // Pin 9 to control servo
PWM_Mode_Setup();
}
void loop(){
if(millis()-time>=20){ // interval 0.02 seconds
time=millis(); // get the current time of programme
if(up){ // judge the condition
if(pos>=0 && pos<=179){
pos=pos+1; // in steps of 1 degree
myservo.write(pos); // tell servo to go to position in variable 'pos'
}
if(pos>179) up= false; // assign the variable again
}
else {
if(pos>=1 && pos<=180){
pos=pos-1;
myservo.write(pos);
}
if(pos<1) up=true;
}
}
if(millis()-urmTimer>50){
urmTimer=millis();
PWM_Mode();
}
}
void PWM_Mode_Setup(){
pinMode(URTRIG,OUTPUT); // A low pull on pin COMP/TRIG
digitalWrite(URTRIG,HIGH); // Set to HIGH
pinMode(URPWM, INPUT); // Sending Enable PWM mode command
for(int i=0;i<4;i++){
Serial.write(EnPwmCmd[i]);
}
}
void PWM_Mode(){ // a low pull on pin COMP/TRIG triggering a sensor reading
digitalWrite(URTRIG, LOW);
digitalWrite(URTRIG, HIGH); // reading Pin PWM will output pulses
unsigned long DistanceMeasured=pulseIn(URPWM,LOW);
if(DistanceMeasured==50000){ // the reading is invalid.
Serial.print("Invalid");
}
else{
Distance=DistanceMeasured/50; // every 50us low level stands for 1cm
}
Serial.print("Distance=");
Serial.print(Distance);
Serial.println("cm");
}
Resources
- Arduino Library from milesburton(IDE 0023 and below)
- Arduino Library from Lauren(Only Arduino IDE 1.0)
Go Shopping URM37 V3.2 Ultrasonic Sensor Manual - Rev 2.2 (SKU:SEN0001)



