USER MANUAL
MAY 6, 2020 ยท BY ZHENGJIE XUAN, CHENG CHE, YAWEN PENG โ
Contents
This directory helps you quickly install and set up.
Demo
After completing the above settings, this page will help you get started with xbee_api by explaining this Demo.
*Before running, remember to add the workspace of the xbee_api package to the ROS environment variable.
*The demo takes two virtual machines linked to XBee module as an example.
1. Launch ROS core.
roscore
2. Run xbee_api_node.py in the xbee_api package.
rosrun xbee_api xbee_api_node.py
*If you get an error at this step, please go to Some Issues That Need Attention first.
3. Run xbee_network_detection_client.py in the xbee_api package.
rosrun xbee_api xbee_network_detection_client.py
Observe the terminal which is running xbee_api_node.py.
rosrun xbee_api xbee_api_node.py
{'status': '\x00', 'frame_id': '1', 'type': 'AT_Command_Response', 'command': 'ND', 'response': {'status': '\x00', 'parent_address': '\xff\xfe', 'profile_id': '\xc1\x05', 'source_addr_16': '\x00\x00', 'device_type': '\x00', 'node_identifier': '1', 'source_addr_64': '\x00\x13\xa2\x00A\x9b_\xb4', 'manufacturer_id': '\x10\x1e'}}
# 1st XBee device parameters returned (Local XBee module's parameters).
{'1': '\x00\x13\xa2\x00A\x9b_\xb4'}
{0: '1'}
# Through these two lines, the node identifier of the local XBee module is 1, and the corresponding 64-bit address is shown above.
{'status': '\x00', 'frame_id': '1', 'type': 'AT_Command_Response', 'command': 'ND', 'response': {'status': '\x00', 'parent_address': '\xff\xfe', 'profile_id': '\xc1\x05', 'source_addr_16': '\xacB', 'device_type': '\x01', 'node_identifier': '2', 'source_addr_64': '\x00\x13\xa2\x00A\x9bN;', 'manufacturer_id': '\x10\x1e'}}
# 2nd XBee device parameters returned (Remote XBee module's parameters).
{'1': '\x00\x13\xa2\x00A\x9b_\xb4', '2': '\x00\x13\xa2\x00A\x9bN;'}
{0: '1', 1: '2'}
# Through these two lines, the node identifier of the remote XBee module is 2, and the corresponding 64-bit address is shown above.
4. Repeat the same steps on another virtual machine and in the terminal which is running xbee_api_node.py we get.
rosrun xbee_api xbee_api_node.py
{'status': '\x00', 'frame_id': '1', 'type': 'AT_Command_Response', 'command': 'ND', 'response': {'status': '\x00', 'parent_address': '\xff\xfe', 'profile_id': '\xc1\x05', 'source_addr_16': '\xacB', 'device_type': '\x01', 'node_identifier': '2', 'source_addr_64': '\x00\x13\xa2\x00A\x9bN;', 'manufacturer_id': '\x10\x1e'}}
# 1st XBee device parameters returned (Local XBee module's parameters).
{'2': '\x00\x13\xa2\x00A\x9bN;'}
{0: '2'}
# Through these two lines, the node identifier of the local XBee module is 2, and the corresponding 64-bit address is shown above.
{'status': '\x00', 'frame_id': '1', 'type': 'AT_Command_Response', 'command': 'ND', 'response': {'status': '\x00', 'parent_address': '\xff\xfe', 'profile_id': '\xc1\x05', 'source_addr_16': '\x00\x00', 'device_type': '\x00', 'node_identifier': '1', 'source_addr_64': '\x00\x13\xa2\x00A\x9b_\xb4', 'manufacturer_id': '\x10\x1e'}}
# 2nd XBee device parameters returned (Remote XBee module's parameters).
{'1': '\x00\x13\xa2\x00A\x9b_\xb4', '2': '\x00\x13\xa2\x00A\x9bN;'}
{0: '2', 1: '1'}
# Through these two lines, the node identifier of the remote XBee module is 1, and the corresponding 64-bit address is shown above.
The XBee parameters returned by the two virtual machine terminals prove the correctness of each other.
5. Now let's try to communicate between two virtual machines.
Before runuing test.py, let's do some preparations first. Open a terminal and enter:
*Please repeat this step 5 on two virtual machines.
rostopic echo /sending_messages
This will listen to and show any messages is publishing to /sending_messages topic.
Then open a new terminal and enter:
rostopic echo /received_data
This will listen to and show any messages is publishing to /received_data topic.
6. Open a new terminal and run test.py in xbee_api package.
rosrun xbee_api test.py
If you can see the same result as the video below, it means you have succeeded.
Code explanation
The following is the code of test.py in the xbee_api package. Green text is code comments.
*path: [ws]/src/xbee_api/scripts/test.py
#!/usr/bin/env python
import rospy
import std_msgs.msg
import math
import sys
from xbee_api.msg import xbee_msgs
from ackermann_msgs.msg import AckermannDriveStamped, AckermannDrive
from geometry_msgs.msg import Twist
def sending_messages():
####
# This method publishes ROS messages to /sending_message at a certain frequency.
####
# Initialize node called test.
rospy.init_node('test')
# Define a publisher to publish a ROS topic /sending_messages. The message type of this topic is xbee_msgs.
pub1 = rospy.Publisher('sending_messages', xbee_msgs, queue_size=10)
# The transmission frequency can be controlled by setting the parameters of this function. And the unit is Hz.
rate = rospy.Rate(4)
# Instantiate an xbee_msgs message.
msg = xbee_msgs()
# Set the destination device for unicast or broadcast, identified by node identifier.
# Format msg.node_identifier = '01 02 15 16 ...'
msg.node_identifier = '02' # unicast/multicast
# Set node identifier to '00' to broadcast. XBee module's broadcast performance is not excellent. If you want to send broadcast information at a high frequency, it is recommended to use multicast to write the node identifier of all devices in the node_identifier to achieve the purpose of broadcasting.
# msg.node_identifier = '00' # broadcast
# Start a loop to publish messages
while not rospy.is_shutdown():
A = AckermannDriveStamped()
A.header.frame_id = "test"
A.header.stamp = rospy.Time.now()
A.drive.speed = 2.5
A.drive.steering_angle = math.pi/2.0
msg.ackermannS = A
pub1.publish(msg)
rate.sleep()
def sending_messages_once():
####
# This method publishes one certain ROS message to /sending_messages_once topic.
####
rospy.init_node('test')
pub2 = rospy.Publisher('sending_messages_once', xbee_msgs, queue_size=10)
rate = rospy.Rate(10)
msg = xbee_msgs()
msg.node_identifier = '01 02'
# msg.node_identifier = '00'
A = AckermannDriveStamped()
A.header.frame_id = "test"
A.header.stamp = rospy.Time.now()
A.drive.speed = 2.5
A.drive.steering_angle = math.pi/2.0
msg.ackermannS = A
once = False
while not once:
connections = pub2.get_num_connections()
if connections > 0:
pub2.publish(msg)
once = True
else:
rate.sleep()
if __name__ == "__main__" :
try:
sending_messages()
# sending_messages_once()
except rospy.ROSInterruptException:
pass
The following uses the sending_message () method as an example to explain the code. This method publishes ROS messages to /sending_message at a certain frequency.
rospy.init_node('test')
Initialize the test node.
pub1 = rospy.Publisher('sending_messages', xbee_msgs, queue_size=10)
Define a publisher to publish a ROS topic /sending_messages. The message type of this topic is xbee_msgs.
rate = rospy.Rate(4)
rate.sleep()
These two function maintaining a particular rate for a loop. In this example is 4 Hz.
msg = xbee_msgs()
Instantiate an xbee_msgs message.
*The following part will focus on explaining xbee_msgs. path: [ws]/src/xbee_api/msg/xbee_msgs
string node_identifier
ackermann_msgs/AckermannDriveStamped ackermannS
You can see that xbee_msgs is composed of two kinds of messages, which are string messages node_identifier and ackermann_msgs/AckermannDriveStamped type messages ackermannS. The most important part of this is.
string node_identifier
It specifies the destination device for sending messages. Its format is for example โ01 03 05 ...โ The two-digit node identifier is separated by a space, and the value range is 0 ~ 99. And after it can be any ROS message not just ackermann_msgs. Users can customize according to their own needs.
Back to the sending_messages() function.
msg.node_identifier = '02'
As mentioned above, set the node_identifier of msg to 02. To send a message to the XBee device with node identifier 2. With the xbee_network_detection_client.py introduced earlier, the message free transmission function under the same Zigbee network can be achieved.
Some Issues That Need Attention
1. If the following problems occur while running the node.
rosrun xbee_api xbee_api_node.api [rosrun] Couldn't find executable named xbee_api_node.api below /home/user/[ws]/src/xbee_api
If you can be sure that your file exists in this path, it is likely that the python file does not have executable permissions. Use the following command in the terminal to add permissions to the python files.
chmod +x pathtofiles/file1.py pathtofiles/file2.py pathtofiles/file3.py ...
2. The following is the code of xbee_api_node.py in the xbee_api package.
*path: [ws]/src/xbee_api/scripts/xbee_api_node.py
#!/usr/bin/env python
from xbee import XBeeDevice
import serial
import rospy
import sys
import cStringIO
import threading
import std_msgs.msg
import std_srvs.srv
from xbee_api.msg import xbee_msgs
#####################
PORT = '/dev/ttyUSB0'
#####################
BAUD_RATE = 9600
BROADCAST = b'\x00\x00\x00\x00\x00\x00\xFF\xFF'
ser = serial.Serial(PORT, BAUD_RATE)
xbee = XBeeDevice(ser)
class xbee_api_node:
def __init__(self):
self.remote_xbee_node_identifier = {}
self.remote_xbee_addr_64 = {}
self.flag = 0
sub1 = rospy.Subscriber('sending_messages', xbee_msgs, self.xbee_send_data)
sub2 = rospy.Subscriber('sending_messages_once', xbee_msgs, self.xbee_send_data_once)
srv = rospy.Service('xbee_network_detection', std_srvs.srv.Empty, self.xbee_network_detection)
receive = threading.Thread(target=self.xbee_receive_data)
receive.start()
def xbee_send_data(self, data):
destination = data.node_identifier
addr = ''
# Serialize
data.node_identifier = self.remote_xbee_node_identifier[0]
output = cStringIO.StringIO()
data.serialize(output)
serialized_data = output.getvalue() # Get the String value of the message
output.close() # Always close the stream
if destination == '00' :
print('Is broadcasting messages')
length = xbee.send('Zigbee_Transmit_Request', frame_id='1', dest_addr_64=BROADCAST, data=serialized_data)
print('Frame length: %d' %length)
else:
for num in destination:
addr += num
if num == ' ':
addr = ''
continue
elif len(addr) == 2:
print('Is sending messages to %s' %addr)
addr = int(addr)
addr = str(addr)
try:
length = xbee.send('Zigbee_Transmit_Request', frame_id='1', dest_addr_64=self.remote_xbee_addr_64[addr], data=serialized_data)
print('Frame length: %d' %length)
except KeyError:
raise KeyError('There is no node {0} in this network.'.format(addr))
addr = ''
def xbee_send_data_once(self, data):
destination = self.remote_xbee_addr_64[data.node_identifier]
# Serialize
data.node_identifier = int(self.remote_xbee_node_identifier[0])
output = cStringIO.StringIO()
data.serialize(output)
serialized_data = output.getvalue() # Get the String value of the message
output.close() # Always close the stream
if destination == '00' :
print('Is broadcasting messages')
length = xbee.send('Zigbee_Transmit_Request', frame_id='1', dest_addr_64=BROADCAST, data=serialized_data)
print('Frame length: %d' %length)
else:
for num in destination:
addr += num
if num == ' ':
addr = ''
continue
elif len(addr) == 2:
print('Is sending messages to %s' %addr)
addr = int(addr)
addr = str(addr)
try:
length = xbee.send('Zigbee_Transmit_Request', frame_id='1', dest_addr_64=self.remote_xbee_addr_64[addr], data=serialized_data)
print('Frame length: %d' %length)
except KeyError:
raise KeyError('There is no node {0} in this network.'.format(addr))
addr = ''
def xbee_network_detection(self, req):
self.flag = 1
xbee.send('AT_Command', frame_id='1', command='ND')
return std_srvs.srv.EmptyResponse()
def xbee_receive_data(self):
pub = rospy.Publisher('received_data', xbee_msgs, queue_size=10)
rate = rospy.Rate(10)
i = 0
while not rospy.is_shutdown():
data = xbee.read()
if self.flag == 1:
self.remote_xbee_addr_64.clear()
self.remote_xbee_node_identifier.clear()
i = 0
if data['type'] == 'Zigbee_Receive_Packet' :
rawdata = data['rx_data']
#deserialize
msg = xbee_msgs()
msg.deserialize(rawdata)
pub.publish(msg)
elif data['type'] == 'Zigbee_Transmit_Status' :
print(xbee.deliver_status[data['deliver_status']])
elif data['command'] == 'ND' :
self.flag = 0
response = data['response']
print(data)
self.remote_xbee_node_identifier[i] = response['node_identifier']
self.remote_xbee_addr_64[response['node_identifier']] = response['source_addr_64']
i += 1
print(self.remote_xbee_addr_64)
print(self.remote_xbee_node_identifier)
else :
print(data)
rate.sleep()
if __name__ == '__main__':
rospy.init_node('xbee_api_node')
xbee_api = xbee_api_node()
rospy.spin()
Let's only focus on the green # emphasized part.
#####################
PORT = '/dev/ttyUSB0'
#####################
Since the USB port on the existing f1 / 10 car has been connected to other devices, the value of PORT should also be changed in response. Use the following command in the terminal to view the port connected devices.
dmesg | grep ttyUSB* [ 2238.702250] usb 2-2.1: FTDI USB Serial Device converter now attached to ttyUSB0
This is the end of the FF1RR project user manual. If you want to know more about XBee and XBee API mode, please go to the Decuments page.
Please Email us if there are any problem.