Compare commits
1 Commits
spiri_test
...
master
Author | SHA1 | Date |
---|---|---|
Benjamin Ramtoula | a360a8d144 |
|
@ -1 +0,0 @@
|
|||
.vscode
|
|
@ -34,11 +34,12 @@ find_package(catkin REQUIRED COMPONENTS
|
|||
## catkin specific configuration ##
|
||||
###################################
|
||||
|
||||
|
||||
catkin_package(
|
||||
INCLUDE_DIRS include
|
||||
LIBRARIES xbee_setup
|
||||
# LIBRARIES xbee_ros_node
|
||||
CATKIN_DEPENDS roscpp std_msgs mavros_msgs
|
||||
DEPENDS Boost
|
||||
# DEPENDS system_lib
|
||||
)
|
||||
|
||||
###########
|
||||
|
@ -52,34 +53,25 @@ add_definitions(
|
|||
|
||||
## Specify additional locations of header files
|
||||
include_directories(
|
||||
include
|
||||
${xbee_ros_node_INCLUDE_DIRS}
|
||||
include ${xbee_ros_node_INCLUDE_DIRS}
|
||||
${catkin_INCLUDE_DIRS}
|
||||
${Boost_INCLUDE_DIRS}
|
||||
${BOOST_INCLUDEDIR}
|
||||
)
|
||||
|
||||
add_library(xbee_setup
|
||||
src/XBeeSetup.cpp
|
||||
src/XBeeModule.cpp
|
||||
src/XMLConfigParser.cpp
|
||||
)
|
||||
|
||||
add_executable(xbee_mav src/Xbee.cpp src/XBeeFrame.cpp src/SerialDevice.cpp src/CommunicationManager.cpp src/PacketsHandler src/frame_generators.cpp)
|
||||
target_link_libraries(xbee_mav xbee_setup ${catkin_LIBRARIES})
|
||||
|
||||
add_executable(xbee_config src/XMLConfigParser.cpp src/main.cpp)
|
||||
target_link_libraries(xbee_config xbee_setup ${catkin_LIBRARIES})
|
||||
add_executable(xbee_mav src/Xbee.cpp src/XBeeFrame.cpp src/SerialDevice.cpp src/CommunicationManager.cpp src/PacketsHandler)
|
||||
target_link_libraries(xbee_mav ${catkin_LIBRARIES})
|
||||
|
||||
add_executable(xbee_config src/main.cpp src/XBeeModule.cpp src/XMLConfigParser.cpp)
|
||||
target_link_libraries(xbee_config ${catkin_LIBRARIES})
|
||||
|
||||
#add_executable(test_controller src/TestController.cpp)
|
||||
#target_link_libraries(test_controller ${catkin_LIBRARIES})
|
||||
|
||||
|
||||
add_executable(test_buzz src/TestBuzz.cpp)
|
||||
target_link_libraries(test_buzz ${catkin_LIBRARIES})
|
||||
|
||||
add_executable(test_buzz_cyclic src/TestBuzzCyclic.cpp)
|
||||
target_link_libraries(test_buzz_cyclic ${catkin_LIBRARIES})
|
||||
|
||||
#############
|
||||
## Install ##
|
||||
#############
|
||||
|
@ -89,3 +81,4 @@ target_link_libraries(test_buzz_cyclic ${catkin_LIBRARIES})
|
|||
#############
|
||||
## Testing ##
|
||||
#############
|
||||
|
||||
|
|
266
README.md
266
README.md
|
@ -1,186 +1,128 @@
|
|||
# XbeeMav
|
||||
## Description
|
||||
XbeeMav
|
||||
=========================
|
||||
|
||||
The "xbee_ros_node" package provides many tools (ROS nodes) to configure, test and communicate Xbee devices.
|
||||
Four nodes are provided in the package:
|
||||
* xbee_config
|
||||
* xbee_mav
|
||||
* test_controller
|
||||
* test_buzz
|
||||
Description:
|
||||
============
|
||||
|
||||
The "test_controller" and the "test_buzz" are dummy nodes. They are used only for testing purposes. The "xbee_config" node is used to configure the Xbees. The "xbee_mav" is used to communicates between Xbee devices in different modes (e.g. SOLO and SWARM).
|
||||
XbeeMav allows to configure, test and communicate with Xbee devices through ROS, and specifically through [mavros](http://wiki.ros.org/mavros).
|
||||
|
||||
## Prerequisites
|
||||
Requirements
|
||||
============
|
||||
|
||||
* Linux OS
|
||||
* ROS
|
||||
* Serial device drivers. For FTDI, the Virtual COM port (VCP) drivers are mandatory (http://www.ftdichip.com/Drivers/VCP.htm).
|
||||
* ROS **base** binary distribution (Indigo or Kinetic):
|
||||
|
||||
## Configuration of Xbee devices
|
||||
The steps for installing ROS Kinetic on Ubuntu are detailed [here](https://wiki.ros.org/kinetic/Installation/Ubuntu).
|
||||
|
||||
To configure an Xbee device, the "xbee_config" node is required. To build the "xbee_config" node:
|
||||
* ROS additionnal dependencies:
|
||||
|
||||
1. Build the package:
|
||||
You will need the [mavros](http://wiki.ros.org/mavros) packages.
|
||||
```
|
||||
sudo apt-get install ros-<distro>-mavros ros-<distro>-mavros-extras
|
||||
```
|
||||
|
||||
$ cd ~/catkin_ws
|
||||
$ catkin_make
|
||||
* XCTU
|
||||
|
||||
To configure an Xbee device run the "xbee_config" node. By default, the VCP and the baud rate are respectively "/dev/ttyUSB0" and "9600". Before running the “config” node, please make sure:
|
||||
You will need the XCTU application for the initial configuration of new XBees.
|
||||
It can be downloaded [here](https://www.digi.com/products/iot-platform/xctu#productsupport-utilities).
|
||||
|
||||
1. The Xbee device is plugged.
|
||||
2. The serial adapter driver is installed.
|
||||
3. You have full access to the correspondent serial port (e.g. ttyUSB0):
|
||||
* XBee modules
|
||||
|
||||
$ sudo chmod 666 /dev/ttyUSB0
|
||||
|
||||
Now you can run the "xbee_config" node (after running roscore):
|
||||
|
||||
$ cd ~/catkin_ws
|
||||
$ rosrun xbee_ros_node xbee_config /dev/ttyUSB0 9600
|
||||
|
||||
If this command generates an error:
|
||||
|
||||
* Error: open: No such file or directory:
|
||||
1. Make sure the Xbee device is plugged.
|
||||
2. Make sure the appropriate driver is installed correctly.
|
||||
3. Make sure the path to the VCP (e.g. /dev/ttyUSB0) is correct.
|
||||
4. Install the newest Xbee firmware with “XCTU” and Write the default config.
|
||||
|
||||
* Error: open: Permission denied:
|
||||
|
||||
You do not have full access to the serial port. Please execute these commands:
|
||||
|
||||
$ sudo chmod 666 /dev/ttyUSB0
|
||||
|
||||
* Time Out: The Xbee Module is Not Responding:
|
||||
|
||||
Baud rate mismatch. Please make sure the introduced baud rate (e.g. 9600) matches the baud rate used by the Xbee (by default is 9600). If the Xbee was previously configured with the “xbee_config” node the baud rate will be 230400.
|
||||
|
||||
The configuration will be loaded from "Resources/Xbee_Config.xml". Most of the existing values in the config file are optimized for Digi-Mesh. Some parameters are default values. However, all parameters can be edited. Please refer to **Table.1** before editing any parameter. More details can be found in “Xbee_Manual.pdf”. The commands table is in Chapter 3 (page 28).
|
||||
|
||||
**Table.1:** Most relevant Xbee Parameters.
|
||||
|
||||
| Key | Name | Chosen Parameter | Justification for chosen setting |
|
||||
|:---:|:-------------:|:-----------------:|:---------------------------------:|
|
||||
|CM | Channel Mask | 7FFF | The channels should be allowed to jump on any available channel (Unless a particular channel is very bad).|
|
||||
|HP | Preamble ID | 1 |This parameter shouldn't be left as is as new not configured radios transmit through this default preamble setting and cause interference by default. Any value from 1-7 should be fine.|
|
||||
|ID | Network ID | 5FFF | As with HP, this parameter should be changed from its default value because it is a factory setting that will introduce new not yet configured radios to the network. Any other value lower than 7FFF should be fine.|
|
||||
|MT | Broadcast Multi-Transmits | 3 | MAC-level re-transmits. No reason for change until thoroughly tested.|
|
||||
|PL | TX Power Level | 4 | Should always be Highest [4] unless very high interference is noted (unlikely in our use case). Should only be decreased for range tests.|
|
||||
|RR | Unicast Retries | A | MAC-level retries. No reason for change until thoroughly tested.|
|
||||
| CE | Routing/Messaging Mode | 0 |Should be standard for DigiMesh. (Needs validating)|
|
||||
|BH | Broadcast Hops | 0 | When set to 0, the broadcast hops will occur until NH is attained.|
|
||||
| NH | Network Hops | 7 | The maximum number of hops throughout the network. We could potentially link this parameter to the minimum necessary data bandwitdth (more hops = less bandwitdh).|
|
||||
| MR | Mesh Unicast Retries | 1 | No reason for change until thoroughly tested.|
|
||||
|NN | Network Delay Slots | 3 | Random delay to alleviate network congestion, especially when broadcasting. Needs to be tested in a very dense mesh.|
|
||||
|DH | Destination Addr.High | 0 | Should be left to default value which will broadcast a message if entering AT mode (even though we will stay in API mode).|
|
||||
|DL | Destination Addr. Low | FFFF | Should be left to default value which will broadcast a message if entering AT mode (even though we will stay in API mode).|
|
||||
|NI | Node Identifier | ‘Node 1’ | This string could be set to a useful identifier for us. It allows up to a 20 characters long ASCII string. Its use needs to be evaluated with the team.|
|
||||
|NT | Network Discov. Back-off| 82 | This value represents a timeout for network discovery, the value is multiplied by 100ms. Network discovery is basically transparent to us (the user).|
|
||||
|NO | Network Discov. Options | 0 | Bit 2 of this bitfield adds RSSI to signal, could be useful for us.|
|
||||
|CI | Cluster ID | 11 | Parameter to be studied. May be useful to identify swarms or camps.|
|
||||
|EE | Encryption Enable | 0 | Enabling encryption slightly impacts the performance (2% according to data from manual) and should be activated. This option almost completely disables the existing possibilities for accidental or voluntary (hacking) interference from other radios.|
|
||||
|KY | AES Encryption Key | empty | 128-bit AES Key. To be generated and shared across all radios.|
|
||||
|BD | Baud Rate | 230400 | To take advantage of the full transmission rate (theoretically 200 kbps), the serial communication baud rate should be adjusted according to the bandwidth.|
|
||||
|NB | Parity | 0 | Default. |
|
||||
|SB | Stop Bits | 0 | Default. |
|
||||
|RO | Packetization Timeout | 3 |Default.|
|
||||
|FT | Flow Control Threshold | 13F | Since we are using the highest baud rate, we might need to increase the flow control threshold. Testing will tell us if the integrity of the data is fine.|
|
||||
|AP | API Enable | 1 | The XBee has to be set to API Mode to receive API frames. This allows recovering useful information in the headers of the frames such as source and destination address. We shouldn't ever need to escape API mode so we chose option [1]. Otherwise, the escape bytes would have to be escaped each time they occur. |
|
||||
|AO | API Options | 0 | Will need to change to [1] (Explicit Rx Indicator) if we wand to be able to read Cluster ID. Otherwise, not very useful. |
|
||||
|
||||
## Test two Xbee devices
|
||||
|
||||
We consider the following setup (**Fig.1**). The block (Drone + Manifold) can be replaced by any Desktop/Laptop meeting the prerequisites.
|
||||
|
||||
**Fig.1:** Experimental Setup:
|
||||
![fig1](Resources/Fig1.png)
|
||||
|
||||
One of the drones will behave as a Master while the other one will act as a Slave. The Master drone will send commands to the Slave drone.
|
||||
Each drone is running a dummy flight controller node "test_controller". According to the drone type Master/Slave, the "test_controller" node will respectively send or receive and display a command. The commands in the Master drone will be introduced with the keyboard. When a command is received in the Slave drone, it will be printed on the screen. The following table (**Table.2**) depicts the keys of each command:
|
||||
|
||||
**Table.2:** Keys and Commands.
|
||||
|
||||
| Keys | Commands |
|
||||
|:----:|:---------:|
|
||||
| 7 | Take Off|
|
||||
| 8 | Land |
|
||||
| 9 | Return To Launch |
|
||||
| 21 | New Waypoint |
|
||||
| 22 | Start Mission |
|
||||
| 23 | Start Mission |
|
||||
We have tested this with the [Digi XBee-PRO 900HP](https://www.digi.com/products/embedded-systems/rf-modules/sub-1-ghz-modules/xbee-pro-900hp), the [Digi XBee SX (900MHz)](https://www.digi.com/products/embedded-systems/rf-modules/sub-1-ghz-modules/xbee-sx) and the [Digi XBee SX 868](https://www.digi.com/products/embedded-systems/rf-modules/sub-1-ghz-modules/digi-xbee-sx-868).
|
||||
|
||||
|
||||
**Fig.2:** ROS nodes running on the drone:
|
||||
![fig2](Resources/Fig2.png)
|
||||
Configure the XBees.
|
||||
===========
|
||||
|
||||
The communication between both drones is performed with Xbees. The “xbee_mav” node (**Fig.2**) will handle all communications with other ROS nodes (test_controller(Flight Controller) or test_buzz (ROS Buzz)) and the connected Xbee device. Therefore, both Xbees must be configured for Digi-Mesh with the maximum baud rate (230400).
|
||||
We recognize two modes of communications:
|
||||
* SOLO mode: The "xbee_mav" will communicate only with the "test_controller" through services. By default, one of the following services will be active according to the drone type (Master/Slave):
|
||||
* “xbee_cmd”: The drone is Master (The server is implemented in the "xbee_mav" side while the client is implemented in the "test_controller" side).
|
||||
* “mav_dji_cmd”: The drone is Slave (The server is implemented in the "test_controller" side while the client is implemented in the "xbee_mav" side).
|
||||
* SWARM mode: The "xbee_mav" will communicate only with "test_buzz" through topics. (“inMavlink” and “outMavlink”).
|
||||
You first need to put the right configuration on the XBees using XCTU.
|
||||
We provide some profile files for both XBee modules we have used in `Resources/xctu_profiles`:
|
||||
- [xbee_pro_900_hp.xpro](Resources/xctu_profiles/xbee_pro_900_hp.xpro) for the Digi XBee-PRO 900HP.
|
||||
- [xbee_sx.xpro](Resources/xctu_profiles/xbee_sx.xpro) for the Digi XBee SX and Digi XBee SX 868.
|
||||
|
||||
All topics and services names of the “xbee_mav” node can be edited in the launch file "launch/xbeemav.launch". For other nodes (test_controller and test_buzz), topics and services names are hardcoded. Thus, they need to be modified in the source code.
|
||||
In order to load the profiles, open XCTU and connect the XBee module to your computer.
|
||||
|
||||
#### SOLO mode
|
||||
You will first need to add the XBee module. You can do so by clicking on the **Discover radio modules** button:
|
||||
|
||||
The "test_controller" node is needed:
|
||||
1. Uncomment the following lines in "CMakeLists.txt":
|
||||
add_executable(test_controller src/TestController.cpp)
|
||||
target_link_libraries(test_controller ${catkin_LIBRARIES})
|
||||
2. Build the package:
|
||||
$ cd ~/catkin_ws
|
||||
$ catkin_make
|
||||
3. Run the "test controller" node in Matser/Slave (after running roscore):
|
||||
$ cd ~/catkin_ws
|
||||
$ rosrun xbee_ros_node test_controller master
|
||||
4. Run the "xbee_mav" node in SOLO mode. The drone type (Master/Slave) and the communication mode (SOLO/SWARM) need to be specified for the "xbee_mav". You can change these parameters in the launch file “launch/xbeemav.launch”:
|
||||
$ cd ~/catkin_ws
|
||||
$ roslaunch xbee_ros_node xbeemav.launch
|
||||
5. Introduce some commands to the "test_controller". If the network was configured correctly, commands sent from one side should be received and displayed in the opposite side.
|
||||
![](Resources/xctu_images/discovery_icon.png)
|
||||
|
||||
#### SWARM mode
|
||||
Select the port where you have connected the XBee, the parameters to search for, and scan.
|
||||
The XBee module should be found, and you can then start configuring it.
|
||||
|
||||
The "test_buzz" node is required:
|
||||
1. Uncomment the following lines in "CMakeLists.txt":
|
||||
add_executable(test_buzz src/TestBuzz.cpp)
|
||||
target_link_libraries(test_buzz ${catkin_LIBRARIES})
|
||||
2. Build the package
|
||||
$ cd ~/catkin_ws
|
||||
$ catkin_make
|
||||
3. Run the "ros_buzz" node. This node is independent of drone type:
|
||||
$ cd ~/catkin_ws
|
||||
$ rosrun xbee_ros_node test_buzz
|
||||
4. Run the "xbee_mav" node in SWARM mode. Run one drone as Master and the other one as Slave (Modify the launch file).
|
||||
$ cd ~/catkin_ws
|
||||
$ roslaunch xbee_ros_node xbeemav.launch
|
||||
From the configuration operating mode:
|
||||
|
||||
Random payloads (Mavlink messages) will be created in the Master drone and transferred through the Xbees to the Slave drone for display. Payloads are arrays with random sizes of random 64 bits integers.
|
||||
![](Resources/xctu_images/configuration.png)
|
||||
|
||||
## Communicate drones in a Swarm
|
||||
You can load the appropriate configuration profile from `Resources/xctu_profiles` by selecting the **Load configuration profile** option:
|
||||
|
||||
We consider the same setup in the testing phase (**Fig.1**). The "test_controller" and the "test_buzz" dummy nodes need to be replaced with real ones (“fligh_controller” and “ros_buzz”).
|
||||
You can download the real nodes by clicking on the correspondent link:
|
||||
* flight_controller : (https://git.mistlab.ca/dasto/djiros_ws)
|
||||
* ros_buzz : (https://github.com/MISTLab/ROSBuzz.git)
|
||||
![](Resources/xctu_images/load_profile.png)
|
||||
|
||||
To run drones in SWARM mode you need to:
|
||||
1. Build the three packages.
|
||||
2. Run a launch file that will start the flight_controller, ros_buzz and xbee_mav. The "xbee_mav" should run in SWARM mode. The drone type (Master/Slave) is not needed.
|
||||
XCTU might ask to update the firmware to load the profile.
|
||||
|
||||
## ROS services
|
||||
The node xbee_mav provides a ROS service xbee_status that will return information
|
||||
about the xbee module. The information returned depends on the argument passed to
|
||||
the service (example: rosservice call /xbee_status "param_id: 'ARGUMENT'"). The different arguments that can be passed are described below:
|
||||
* id : Returns the xbee module short identifier.
|
||||
* deque_full : returns 1 if the out messages queue is full and 0 otherwise
|
||||
* rssi : Returns the average Received Signal Strength Indicator (RSSI). This RSSI value could be inaccurate since the average is obtained by getting the RSSI of the last message at a fixed frequency without any information about the sender.
|
||||
* trig_rssi_api_avg : Triggers a link testing procedure to obtain the RSSI with all the known nodes in the network. Returns false if there is no other node connected to the network.
|
||||
* trig_rssi_api_ID (where ID should be replaced by a number): Triggers a link testing procedure to obtain the RSSI with the corresponding ID. Returns false if the node is not present on the network.
|
||||
* get_rssi_api_avg : Returns the average of the average RSSI results of the link testing procedures.
|
||||
* get_rssi_api_ID (where ID should be replaced by a number): Returns the average RSSI result of the link testing procedure.
|
||||
* pl_raw_avg : Returns the average of the raw packet loss value among the connected nodes. Returns false if there is no other node connected to the network.
|
||||
* pl_raw_ID (where ID should be replaced by a number): Returns the raw packet loss value between this node and the node ID. Returns false if the node is not present on the network.
|
||||
* pl_filter_avg : same thing as pl_raw_avg but for the filtered value.
|
||||
* pl_filter_ID (where ID should be replaced by a number): same thing as pl_raw_ID but for the filtered value.
|
||||
|
||||
Update the database.
|
||||
===========
|
||||
In order for your XBee module to be recognized, it is necessary to add it to the database file.
|
||||
|
||||
To do so, you need to find the MAC address of your XBee module.
|
||||
|
||||
If you added the module to XCTU, you can read it directly from XCTU:
|
||||
|
||||
![](Resources/xctu_images/mac_address.png)
|
||||
|
||||
The MAC address is also written directly on the module:
|
||||
|
||||
![](Resources/xctu_images/xbee_pro.png) ![](Resources/xctu_images/xbee_sx.jpg)
|
||||
|
||||
Now, you have to add the MAC address to the [Resources/database.xml](Resources/database.xml) file.
|
||||
|
||||
Add a line within the `<Addresses>` and `</Addresses>` tags with the following format, replacing N by an integer ID not yet used in the database file, and MAC_ADDRESS by the MAC address of your XBee module:
|
||||
```
|
||||
<Device Address= "N" >MAC_ADDRESS</Device>
|
||||
```
|
||||
Compilation
|
||||
===========
|
||||
|
||||
```
|
||||
mkdir -p ~/ROS_WS/src
|
||||
cd ~/ROS_WS/src
|
||||
git clone https://github.com/MISTLab/XbeeMav xbeemav
|
||||
cd ..
|
||||
catkin_make
|
||||
```
|
||||
|
||||
Source ROS environment
|
||||
===========
|
||||
|
||||
```
|
||||
source /opt/ros/kinetic/setup.bash
|
||||
source ~/ROS_WS/devel/setup.bash
|
||||
```
|
||||
|
||||
|
||||
|
||||
|
||||
Run
|
||||
===
|
||||
To run the XbeeMav package using the launch file, execute the following:
|
||||
```
|
||||
roslaunch xbee_ros_node xbeemav.launch
|
||||
```
|
||||
|
||||
Publishers
|
||||
-----------
|
||||
|
||||
* /inMavlink [mavros_msgs/Mavlink]
|
||||
|
||||
Subscribers
|
||||
-----------
|
||||
|
||||
* /outMavlink [mavros_msgs/Mavlink]
|
||||
|
||||
Services
|
||||
-------
|
||||
|
||||
* /network_status [mavros_msgs/ParamGet]
|
||||
|
||||
This service can take 3 values:
|
||||
1. `id` for the network id for the XBee module registered in the [database.xml](Resources/database.xml) file.
|
||||
2. `rssi` for the signal strength of last message received.
|
||||
3. `pl_raw_avg` for the average packet loss.
|
|
@ -0,0 +1,232 @@
|
|||
# **_WARNING_ - This is outdated! However it might still contain useful information...**
|
||||
|
||||
## Description
|
||||
|
||||
The "xbee_ros_node" package provides many tools (ROS nodes) to configure, test and communicate Xbee devices.
|
||||
Four nodes are provided in the package:
|
||||
* config
|
||||
* xbee_mav
|
||||
* test_controller
|
||||
* test_buzz
|
||||
|
||||
The "test_controller" and the "test_buzz" are dummy nodes. They are used only for testing purposes. The "config" node is used to configure the Xbees. The "xbee_mav" is used to communicates between Xbee devices in different modes (e.g. SOLO and SWARM).
|
||||
|
||||
## Prerequisites
|
||||
|
||||
* Linux OS
|
||||
* ROS
|
||||
* Serial device drivers. For FTDI, the Virtual COM port (VCP) drivers are mandatory (http://www.ftdichip.com/Drivers/VCP.htm).
|
||||
|
||||
## Configuration of Xbee devices
|
||||
|
||||
To configure an Xbee device, the "config" node is required. To build the "config" node:
|
||||
|
||||
1. Uncomment the following lines in [XbeeMav/CMakeLists.txt](../CMakeLists.txt)`:
|
||||
|
||||
```
|
||||
add_executable(config src/main.cpp src/XbeeModule.cpp src/XMLConfigParser.cpp)
|
||||
target_link_libraries(config ${catkin_LIBRARIES})
|
||||
```
|
||||
|
||||
2. Insert the correct path to the config file “Resources/Xbee_Config.xml” in “XMLConfigParser.cpp” (line 26):
|
||||
```
|
||||
FILE_NAME = “/home/mistlab/catkin_ws/src/xbee_ros_node/Resources/Xbee_Config.xml”`
|
||||
```
|
||||
|
||||
3. Build the package:
|
||||
|
||||
```
|
||||
cd ~/catkin_ws
|
||||
catkin_make
|
||||
```
|
||||
|
||||
To configure an Xbee device run the "config" node. By default, the VCP and the baud rate are respectively "/dev/ttyUSB0" and "9600". Before running the “config” node, please make sure:
|
||||
|
||||
1. The Xbee device is plugged.
|
||||
2. The serial adapter driver is installed.
|
||||
3. You have full access to the correspondent serial port (e.g. ttyUSB0):
|
||||
|
||||
```
|
||||
cd ~/../../dev/
|
||||
sudo chmod 666 ttyUSB0
|
||||
```
|
||||
|
||||
Now you can run the “config” node (after running roscore):
|
||||
```
|
||||
cd ~/catkin_ws
|
||||
rosrun xbee_ros_node config /dev/ttyUSB0 9600
|
||||
```
|
||||
|
||||
If this command generates an error:
|
||||
|
||||
* `Error: open: No such file or directory`:
|
||||
1. Make sure the Xbee device is plugged.
|
||||
2. Make sure the appropriate driver is installed correctly.
|
||||
3. Make sure the path to the VCP (e.g. /dev/ttyUSB0) is correct.
|
||||
4. Install the newest Xbee firmware with “XCTU” and Write the default config.
|
||||
|
||||
* `Error: open: Permission denied`:
|
||||
|
||||
You do not have full access to the serial port. Please execute these commands:
|
||||
|
||||
```
|
||||
cd ~/../../dev/
|
||||
sudo chmod 666 ttyUSB0
|
||||
```
|
||||
|
||||
* `Time Out: The Xbee Module is Not Responding`:
|
||||
|
||||
Baud rate mismatch. Please make sure the introduced baud rate (e.g. 9600) matches the baud rate used by the Xbee (by default is 9600). If the Xbee was previously configured with the “config” node the baud rate will be 230400.
|
||||
|
||||
* `Error: Config File Not Found`:
|
||||
|
||||
The path to the config file is incorrect. Change it in “XMLConfigParser.cpp” (line 26):
|
||||
|
||||
```
|
||||
FILE_NAME = “/home/mistlab/catkin_ws/src/xbee_ros_node/Resources/Xbee_Config.xml”
|
||||
```
|
||||
|
||||
The configuration will be loaded from "Resources/Xbee_Config.xml". Most of the existing values in the config file are optimized for Digi-Mesh. Some parameters are default values. However, all parameters can be edited. Please refer to **Table.1** before editing any parameter. More details can be found in “Xbee_Manual.pdf”. The commands table is in Chapter 3 (page 28).
|
||||
|
||||
**Table.1:** Most relevant Xbee Parameters.
|
||||
|
||||
| Key | Name | Chosen Parameter | Justification for chosen setting |
|
||||
|:---:|:-------------:|:-----------------:|:---------------------------------:|
|
||||
|CM | Channel Mask | 7FFF | The channels should be allowed to jump on any available channel (Unless a particular channel is very bad).|
|
||||
|HP | Preamble ID | 1 |This parameter shouldn't be left as is as new not configured radios transmit through this default preamble setting and cause interference by default. Any value from 1-7 should be fine.|
|
||||
|ID | Network ID | 5FFF | As with HP, this parameter should be changed from its default value because it is a factory setting that will introduce new not yet configured radios to the network. Any other value lower than 7FFF should be fine.|
|
||||
|MT | Broadcast Multi-Transmits | 3 | MAC-level re-transmits. No reason for change until thoroughly tested.|
|
||||
|PL | TX Power Level | 4 | Should always be Highest [4] unless very high interference is noted (unlikely in our use case). Should only be decreased for range tests.|
|
||||
|RR | Unicast Retries | A | MAC-level retries. No reason for change until thoroughly tested.|
|
||||
| CE | Routing/Messaging Mode | 0 |Should be standard for DigiMesh. (Needs validating)|
|
||||
|BH | Broadcast Hops | 0 | When set to 0, the broadcast hops will occur until NH is attained.|
|
||||
| NH | Network Hops | 7 | The maximum number of hops throughout the network. We could potentially link this parameter to the minimum necessary data bandwitdth (more hops = less bandwitdh).|
|
||||
| MR | Mesh Unicast Retries | 1 | No reason for change until thoroughly tested.|
|
||||
|NN | Network Delay Slots | 3 | Random delay to alleviate network congestion, especially when broadcasting. Needs to be tested in a very dense mesh.|
|
||||
|DH | Destination Addr.High | 0 | Should be left to default value which will broadcast a message if entering AT mode (even though we will stay in API mode).|
|
||||
|DL | Destination Addr. Low | FFFF | Should be left to default value which will broadcast a message if entering AT mode (even though we will stay in API mode).|
|
||||
|NI | Node Identifier | ‘Node 1’ | This string could be set to a useful identifier for us. It allows up to a 20 characters long ASCII string. Its use needs to be evaluated with the team.|
|
||||
|NT | Network Discov. Back-off| 82 | This value represents a timeout for network discovery, the value is multiplied by 100ms. Network discovery is basically transparent to us (the user).|
|
||||
|NO | Network Discov. Options | 0 | Bit 2 of this bitfield adds RSSI to signal, could be useful for us.|
|
||||
|CI | Cluster ID | 11 | Parameter to be studied. May be useful to identify swarms or camps.|
|
||||
|EE | Encryption Enable | 0 | Enabling encryption slightly impacts the performance (2% according to data from manual) and should be activated. This option almost completely disables the existing possibilities for accidental or voluntary (hacking) interference from other radios.|
|
||||
|KY | AES Encryption Key | empty | 128-bit AES Key. To be generated and shared across all radios.|
|
||||
|BD | Baud Rate | 230400 | To take advantage of the full transmission rate (theoretically 200 kbps), the serial communication baud rate should be adjusted according to the bandwidth.|
|
||||
|NB | Parity | 0 | Default. |
|
||||
|SB | Stop Bits | 0 | Default. |
|
||||
|RO | Packetization Timeout | 3 |Default.|
|
||||
|FT | Flow Control Threshold | 13F | Since we are using the highest baud rate, we might need to increase the flow control threshold. Testing will tell us if the integrity of the data is fine.|
|
||||
|AP | API Enable | 1 | The XBee has to be set to API Mode to receive API frames. This allows recovering useful information in the headers of the frames such as source and destination address. We shouldn't ever need to escape API mode so we chose option [1]. Otherwise, the escape bytes would have to be escaped each time they occur. |
|
||||
|AO | API Options | 0 | Will need to change to [1] (Explicit Rx Indicator) if we wand to be able to read Cluster ID. Otherwise, not very useful. |
|
||||
|
||||
## Test two Xbee devices
|
||||
|
||||
We consider the following setup (**Fig.1**). The block (Drone + Manifold) can be replaced by any Desktop/Laptop meeting the prerequisites.
|
||||
|
||||
**Fig.1:** Experimental Setup:
|
||||
|
||||
![](Fig1.png)
|
||||
|
||||
One of the drones will behave as a Master while the other one will act as a Slave. The Master drone will send commands to the Slave drone.
|
||||
Each drone is running a dummy flight controller node "test_controller". According to the drone type Master/Slave, the "test_controller" node will respectively send or receive and display a command. The commands in the Master drone will be introduced with the keyboard. When a command is received in the Slave drone, it will be printed on the screen. The following table (**Table.2**) depicts the keys of each command:
|
||||
|
||||
**Table.2:** Keys and Commands.
|
||||
|
||||
| Keys | Commands |
|
||||
|:----:|:---------:|
|
||||
| 7 | Take Off|
|
||||
| 8 | Land |
|
||||
| 9 | Return To Launch |
|
||||
| 21 | New Waypoint |
|
||||
| 22 | Start Mission |
|
||||
| 23 | Start Mission |
|
||||
|
||||
|
||||
**Fig.2:** ROS nodes running on the drone:
|
||||
|
||||
![](Fig2.png)
|
||||
|
||||
The communication between both drones is performed with Xbees. The “xbee_mav” node (**Fig.2**) will handle all communications with other ROS nodes (test_controller(Flight Controller) or test_buzz (ROS Buzz)) and the connected Xbee device. Therefore, both Xbees must be configured for Digi-Mesh with the maximum baud rate (230400).
|
||||
We recognize two modes of communications:
|
||||
* SOLO mode: The "xbee_mav" will communicate only with the "test_controller" through services. By default, one of the following services will be active according to the drone type (Master/Slave):
|
||||
* “xbee_cmd”: The drone is Master (The server is implemented in the "xbee_mav" side while the client is implemented in the "test_controller" side).
|
||||
* “mav_dji_cmd”: The drone is Slave (The server is implemented in the "test_controller" side while the client is implemented in the "xbee_mav" side).
|
||||
* SWARM mode: The "xbee_mav" will communicate only with "test_buzz" through topics. (“inMavlink” and “outMavlink”).
|
||||
|
||||
All topics and services names of the “xbee_mav” node can be edited in the launch file "launch/xbeemav.launch". For other nodes (test_controller and test_buzz), topics and services names are hardcoded. Thus, they need to be modified in the source code.
|
||||
|
||||
#### SOLO mode
|
||||
|
||||
The "test_controller" node is needed:
|
||||
1. Uncomment the following lines in "CMakeLists.txt":
|
||||
```
|
||||
add_executable(test_controller src/TestController.cpp)
|
||||
target_link_libraries(test_controller ${catkin_LIBRARIES})
|
||||
```
|
||||
|
||||
2. Build the package:
|
||||
```
|
||||
cd ~/catkin_ws
|
||||
catkin_make
|
||||
```
|
||||
|
||||
3. Run the "test controller" node in Matser/Slave (after running roscore):
|
||||
```
|
||||
$ cd ~/catkin_ws
|
||||
$ rosrun xbee_ros_node test_controller master
|
||||
```
|
||||
|
||||
4. Run the "xbee_mav" node in SOLO mode. The drone type (Master/Slave) and the communication mode (SOLO/SWARM) need to be specified for the "xbee_mav". You can change these parameters in the launch file “launch/xbeemav.launch”:
|
||||
```
|
||||
cd ~/catkin_ws
|
||||
roslaunch xbee_ros_node xbeemav.launch
|
||||
```
|
||||
|
||||
5. Introduce some commands to the "test_controller". If the network was configured correctly, commands sent from one side should be received and displayed in the opposite side.
|
||||
|
||||
#### SWARM mode
|
||||
|
||||
The "test_buzz" node is required:
|
||||
1. Uncomment the following lines in "CMakeLists.txt":
|
||||
```
|
||||
add_executable(test_buzz src/TestBuzz.cpp)
|
||||
target_link_libraries(test_buzz ${catkin_LIBRARIES})
|
||||
```
|
||||
2. Build the package
|
||||
```
|
||||
cd ~/catkin_ws
|
||||
catkin_make
|
||||
```
|
||||
3. Run the "ros_buzz" node. This node is independent of drone type:
|
||||
```
|
||||
cd ~/catkin_ws
|
||||
rosrun xbee_ros_node test_buzz
|
||||
```
|
||||
4. Run the "xbee_mav" node in SWARM mode. Run one drone as Master and the other one as Slave (Modify the launch file).
|
||||
```
|
||||
cd ~/catkin_ws
|
||||
roslaunch xbee_ros_node xbeemav.launch
|
||||
```
|
||||
|
||||
Random payloads (Mavlink messages) will be created in the Master drone and transferred through the Xbees to the Slave drone for display. Payloads are arrays with random sizes of random 64 bits integers.
|
||||
|
||||
## Communicate drones in a Swarm
|
||||
|
||||
We consider the same setup in the testing phase (**Fig.1**). The "test_controller" and the "test_buzz" dummy nodes need to be replaced with real ones (“fligh_controller” and “ros_buzz”).
|
||||
You can download the real nodes by clicking on the correspondent link:
|
||||
* flight_controller : (https://git.mistlab.ca/dasto/djiros_ws)
|
||||
* ros_buzz : (https://github.com/MISTLab/ROSBuzz.git)
|
||||
|
||||
To run drones in SWARM mode you need to:
|
||||
1. Comment the following lines in “xbee_ros_node/CMakeLists.txt”:
|
||||
```
|
||||
add_executable(config src/main.cpp src/XbeeModule.cpp src/XMLConfigParser.cpp)
|
||||
target_link_libraries(config ${catkin_LIBRARIES})
|
||||
add_executable(test_controller src/TestController.cpp)
|
||||
target_link_libraries(test_controller ${catkin_LIBRARIES})
|
||||
add_executable(test_buzz src/TestBuzz.cpp)
|
||||
target_link_libraries(test_buzz ${catkin_LIBRARIES})
|
||||
```
|
||||
|
||||
2. Build the three packages.
|
||||
3. Run the launch file (this will run the flight_controller, ros_buzz and xbee_mav). The "xbee_mav" should run in SWARM mode. The drone type (Master/Slave) is not needed.
|
|
@ -5,11 +5,11 @@
|
|||
<Parameter Command="CM" Description="Channel Mask">00FFFFFFFFFFF7FFFF</Parameter>
|
||||
<Parameter Command="HP" Description="Preamble ID">1</Parameter>
|
||||
<Parameter Command="ID" Description="Network ID">5FFF</Parameter>
|
||||
<Parameter Command="MT" Description="Broadcast Multi-Transmits">0</Parameter>
|
||||
<Parameter Command="MT" Description="Broadcast Multi-Transmits">3</Parameter>
|
||||
<Parameter Command="PL" Description="TX Power Level">4</Parameter>
|
||||
<Parameter Command="RR" Description="Unicast Retries">A</Parameter>
|
||||
<Parameter Command="CE" Description="Routing/Messaging Mode">0</Parameter>
|
||||
<Parameter Command="BH" Description="Broadcast Hops">1</Parameter>
|
||||
<Parameter Command="BH" Description="Broadcast Hops">0</Parameter>
|
||||
<Parameter Command="NH" Description="Network Hops">7</Parameter>
|
||||
<Parameter Command="MR" Description="Mesh Unicast Retries">1</Parameter>
|
||||
<Parameter Command="NN" Description="Network Delay Slots">3</Parameter>
|
||||
|
@ -63,5 +63,6 @@
|
|||
<Parameter Command="CC" Description="Commande Sequence Character">2B</Parameter>
|
||||
<Parameter Command="CT" Description="Command Mode Time Out">60</Parameter>
|
||||
<Parameter Command="GT" Description="Guard Time">3E8</Parameter>
|
||||
<Parameter Command="DD" Description="Device Type Identifier">B0000</Parameter>
|
||||
</Settings>
|
||||
</XBeeConfig>
|
||||
|
|
Binary file not shown.
|
@ -1,6 +1,18 @@
|
|||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
|
||||
<Addresses>
|
||||
<Device Address= "1" >0013A200417DFE04</Device>
|
||||
<Device Address= "241">0013A20041663D11</Device>
|
||||
<Device Address= "1" >0013A20040D8CA1E</Device>
|
||||
<Device Address= "2" >0013A200415278B8</Device>
|
||||
<Device Address= "3" >0013A2004103B363</Device>
|
||||
<Device Address= "4" >0013A200415278AD</Device>
|
||||
<Device Address= "5" >0013A2004103B356</Device>
|
||||
<Device Address= "6" >0013A200415278B7</Device>
|
||||
<Device Address= "7" >0013A2004098A7A7</Device>
|
||||
<Device Address= "8" >0013A2004098A7BA</Device>
|
||||
<Device Address= "9" >0013A200415A9DDD</Device>
|
||||
<Device Address= "10" >0013A200415A9DE4</Device>
|
||||
<Device Address= "11" >0013A200415A9DDF</Device>
|
||||
<Device Address= "12" >0013A200415A9DDE</Device>
|
||||
<Device Address= "13" >0013A200415A9DE8</Device>
|
||||
|
||||
</Addresses>
|
||||
|
|
|
@ -1,6 +0,0 @@
|
|||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
|
||||
<Addresses>
|
||||
|
||||
<Device Address= "241">0013A20041663D11</Device>
|
||||
</Addresses>
|
Binary file not shown.
After Width: | Height: | Size: 28 KiB |
Binary file not shown.
After Width: | Height: | Size: 16 KiB |
Binary file not shown.
After Width: | Height: | Size: 34 KiB |
Binary file not shown.
After Width: | Height: | Size: 32 KiB |
Binary file not shown.
After Width: | Height: | Size: 64 KiB |
Binary file not shown.
After Width: | Height: | Size: 33 KiB |
Binary file not shown.
Binary file not shown.
|
@ -5,26 +5,33 @@
|
|||
/* September 20, 2016 -- @Copyright Aymen Soussia. All rights reserved. */
|
||||
/* (aymen.soussia@gmail.com) */
|
||||
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "PacketsHandler.h"
|
||||
#include "SerialDevice.h"
|
||||
#include <inttypes.h>
|
||||
#include<thread>
|
||||
#include <std_msgs/UInt8.h>
|
||||
#include<mavros_msgs/CommandCode.h>
|
||||
#include<mavros_msgs/CommandInt.h>
|
||||
#include<mavros_msgs/Mavlink.h>
|
||||
#include <ros/ros.h>
|
||||
#include <mavros_msgs/ParamGet.h>
|
||||
#include <mavros_msgs/ParamValue.h>
|
||||
#include <ros/ros.h>
|
||||
#include <std_msgs/UInt8.h>
|
||||
#include <thread>
|
||||
#include"PacketsHandler.h"
|
||||
#include"SerialDevice.h"
|
||||
|
||||
namespace Mist {
|
||||
|
||||
namespace Xbee {
|
||||
namespace Mist
|
||||
{
|
||||
|
||||
|
||||
namespace Xbee
|
||||
{
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
struct Waypoint_S {
|
||||
struct Waypoint_S
|
||||
{
|
||||
unsigned int latitude;
|
||||
unsigned int longitude;
|
||||
double altitude;
|
||||
|
@ -32,6 +39,7 @@ struct Waypoint_S {
|
|||
unsigned int heading;
|
||||
};
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
class CommunicationManager
|
||||
{
|
||||
|
@ -46,36 +54,40 @@ class CommunicationManager
|
|||
void Run(DRONE_TYPE drone_type, RUNNING_MODE running_mode);
|
||||
|
||||
private:
|
||||
|
||||
const unsigned char START_DLIMITER;
|
||||
const std::size_t LOOP_RATE;
|
||||
const uint8_t DEFAULT_RATE_DIVIDER_RSSI;
|
||||
const uint8_t DEFAULT_RATE_DIVIDER_PACKET_LOSS;
|
||||
const uint16_t DEFAULT_RSSI_PAYLOAD_SIZE;
|
||||
const uint16_t DEFAULT_RSSI_ITERATIONS;
|
||||
|
||||
void Run_In_Solo_Mode(DRONE_TYPE drone_type);
|
||||
void Run_In_Swarm_Mode();
|
||||
/*void Generate_Transmit_Request_Frame(
|
||||
const char* const message,
|
||||
std::string* frame,
|
||||
const unsigned char frame_ID =
|
||||
static_cast<unsigned char>(0x01),
|
||||
const std::string& destination_adssress = "000000000000FFFF",
|
||||
const std::string& short_destination_adress = "FFFF",
|
||||
const std::string& broadcast_radius = "00",
|
||||
const std::string& options = "00");*/
|
||||
//void Check_In_Messages_and_Transfer_To_Topics();
|
||||
void Display_Init_Communication_Failure();
|
||||
//void Convert_HEX_To_Bytes(const std::string& HEX_data,
|
||||
//std::string* converted_data);
|
||||
//void Calculate_and_Append_Checksum(std::string* frame);
|
||||
//void Add_Length_and_Start_Delimiter(std::string* frame);
|
||||
void Send_Mavlink_Message_Callback(
|
||||
const mavros_msgs::Mavlink::ConstPtr& mavlink_msg);
|
||||
void Display_Drone_Type_and_Running_Mode(DRONE_TYPE drone_type,
|
||||
RUNNING_MODE running_mode);
|
||||
bool Serve_Flight_Controller(mavros_msgs::CommandInt::Request &request,
|
||||
mavros_msgs::CommandInt::Response &response);
|
||||
bool Serve_Flight_Controller(mavros_msgs::CommandInt::
|
||||
Request& request, mavros_msgs::CommandInt::Response& response);
|
||||
void Check_In_Messages_and_Transfer_To_Server();
|
||||
void Process_In_Standard_Messages();
|
||||
void Process_In_Acks_and_Pings();
|
||||
void Process_In_Fragments();
|
||||
void Process_In_Packets();
|
||||
void Process_Command_Responses();
|
||||
void Process_Packet_Loss();
|
||||
bool Get_Param(mavros_msgs::ParamGet::Request &req,
|
||||
mavros_msgs::ParamGet::Response &res);
|
||||
bool getRosParams();
|
||||
int getIntParam(std::string name, int default_value);
|
||||
void triggerRssiUpdate();
|
||||
std::string safeSubStr(const std::string strg,
|
||||
const unsigned int index_max) const;
|
||||
bool Get_Param(mavros_msgs::ParamGet::Request& req, mavros_msgs::ParamGet::Response& res);
|
||||
|
||||
Mist::Xbee::SerialDevice serial_device_;
|
||||
Mist::Xbee::PacketsHandler packets_handler_;
|
||||
|
@ -84,7 +96,6 @@ class CommunicationManager
|
|||
Thread_Safe_Deque in_Acks_and_Pings_;
|
||||
Thread_Safe_Deque command_responses_;
|
||||
Thread_Safe_Deque in_packets_;
|
||||
Thread_Safe_Deque in_packet_loss_;
|
||||
ros::NodeHandle node_handle_;
|
||||
ros::Subscriber mavlink_subscriber_;
|
||||
ros::Publisher mavlink_publisher_;
|
||||
|
@ -93,11 +104,10 @@ class CommunicationManager
|
|||
ros::ServiceServer StatusSrv_;
|
||||
std_msgs::UInt8 device_id_out;
|
||||
std::shared_ptr<std::thread> service_thread_; // TO DO delete !?
|
||||
std::uint16_t packet_loss_timer_;
|
||||
uint8_t rate_divider_rssi_;
|
||||
uint8_t rate_divider_packet_loss_;
|
||||
uint16_t rssi_payload_size_;
|
||||
uint16_t rssi_iterations_;
|
||||
};
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
|
|
@ -25,7 +25,6 @@
|
|||
|
||||
#include"MultithreadingDeque.hpp"
|
||||
#include"SerialDevice.h"
|
||||
#include "frame_generators.h"
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
|
@ -39,45 +38,6 @@ namespace Mist
|
|||
namespace Xbee
|
||||
{
|
||||
|
||||
struct Reassembly_Packet_S
|
||||
{
|
||||
uint8_t packet_ID_;
|
||||
std::string packet_buffer_; // TO DO make it shared ptr
|
||||
std::set<uint8_t> received_fragments_IDs_;
|
||||
std::clock_t time_since_creation_; // TO DO use it to delete packets with time out
|
||||
};
|
||||
|
||||
struct On_Line_Node_S
|
||||
{
|
||||
uint64_t device_64_bits_address_;
|
||||
float packet_loss_raw_;
|
||||
float packet_loss_filtered_;
|
||||
uint16_t sent_packets_;
|
||||
uint16_t received_packets_;
|
||||
uint8_t packet_loss_sent_id_;
|
||||
uint8_t packet_loss_received_id_;
|
||||
};
|
||||
|
||||
enum RSSI_API_STATUS
|
||||
{
|
||||
OLD_VALUE,
|
||||
TRIGGERED,
|
||||
NEW_VALUE
|
||||
};
|
||||
|
||||
struct RSSI_Result
|
||||
{
|
||||
uint16_t payload_size;
|
||||
uint16_t iterations;
|
||||
uint16_t success;
|
||||
uint16_t retries;
|
||||
uint8_t result;
|
||||
uint8_t rr;
|
||||
uint8_t max_rssi;
|
||||
uint8_t min_rssi;
|
||||
uint8_t avg_rssi;
|
||||
RSSI_API_STATUS status;
|
||||
};
|
||||
|
||||
//*****************************************************************************
|
||||
class PacketsHandler
|
||||
|
@ -97,39 +57,23 @@ namespace Xbee
|
|||
void Delete_Packets_With_Time_Out();
|
||||
void Deserialize_Mavlink_Message(const char * bytes,
|
||||
mavros_msgs::Mavlink* mavlink_msg, const std::size_t msg_size);
|
||||
uint8_t getDeviceId();
|
||||
uint8_t getDequeFull();
|
||||
float getSignalStrength();
|
||||
float getAPISignalStrength(uint8_t short_node_id);
|
||||
float getRawPacketLoss(uint8_t short_node_id);
|
||||
float getPacketLoss(uint8_t short_node_id);
|
||||
void triggerRssiUpdate();
|
||||
uint8_t triggerAPIRssiUpdate(uint16_t rssi_payload_size,
|
||||
uint16_t rssi_iterations,
|
||||
uint8_t target_id);
|
||||
void processPacketLoss(const char* packet_loss);
|
||||
void sendPacketLoss();
|
||||
uint8_t get_device_id();
|
||||
|
||||
static uint16_t ucharToUint16(unsigned char msb, unsigned char lsb);
|
||||
|
||||
static const uint16_t PACKET_LOSS_UNAVAILABLE;
|
||||
static const uint8_t ALL_IDS;
|
||||
static const uint8_t MAX_WAITING_OUT_MSG;
|
||||
|
||||
private:
|
||||
const std::size_t MAX_PACEKT_SIZE; /* MAX packet size in bytes = 63750 bytes */
|
||||
const std::size_t XBEE_NETWORK_MTU; /* Maximum Transmission Unit of Xbee netwrok = 256 bytes (max payload) - 6 bytes (Header size of each fragment) = 250 bytes */
|
||||
const std::size_t FRAGMENT_HEADER_SIZE; /* Header size of each fragment = 6 bytes */
|
||||
const std::clock_t MAX_TIME_TO_SEND_PACKET; /* Maximum time before dropping a packet = 30 seconds*/
|
||||
;
|
||||
// RSSI constants
|
||||
const std::string RSSI_COMMAND;
|
||||
const float RSSI_FILTER_GAIN; //filter: old * (1.0-GAIN) + new * GAIN
|
||||
const unsigned char START_DLIMITER;
|
||||
|
||||
// Packet Loss
|
||||
const std::string PACKET_LOSS_IDENTIFIER;
|
||||
const uint8_t MAX_PACKET_LOSS_MSG_ID; // used for synchronisation
|
||||
const float PACKET_LOSS_FILTER_GAIN; //filter: new * (1.0-GAIN) + old * GAIN
|
||||
struct Reassembly_Packet_S
|
||||
{
|
||||
uint8_t packet_ID_;
|
||||
std::string packet_buffer_; // TO DO make it shared ptr
|
||||
std::set<uint8_t> received_fragments_IDs_;
|
||||
std::clock_t time_since_creation_; // TO DO use it to delete packets with time out
|
||||
};
|
||||
|
||||
void Insert_Fragment_In_Packet_Buffer(std::string* buffer,
|
||||
const char* fragment, const uint16_t offset, const std::size_t length);
|
||||
|
@ -153,13 +97,31 @@ namespace Xbee
|
|||
void Adjust_Optimum_MT_Number(const std::clock_t elapsed_time,
|
||||
const std::size_t NBR_of_transmission);
|
||||
void Send_SL_and_SH_Commands();
|
||||
void Generate_Transmit_Request_Frame(
|
||||
const char* message,
|
||||
std::string* frame,
|
||||
const std::size_t message_size,
|
||||
const unsigned char frame_ID =
|
||||
static_cast<unsigned char>(0x01),
|
||||
const std::string& destination_adssress = "000000000000FFFF",
|
||||
const std::string& short_destination_adress = "FFFF",
|
||||
const std::string& broadcast_radius = "00",
|
||||
const std::string& options = "00");
|
||||
void Convert_HEX_To_Bytes(const std::string& HEX_data,
|
||||
std::string* converted_data);
|
||||
void Calculate_and_Append_Checksum(std::string* frame);
|
||||
void Add_Length_and_Start_Delimiter(std::string* frame);
|
||||
void Generate_AT_Command(const char* command,
|
||||
std::string* frame,
|
||||
const unsigned char frame_ID =
|
||||
static_cast<unsigned char>(0x01));
|
||||
|
||||
|
||||
float computePercentage(const int16_t numerator, const int16_t denumerator) const;
|
||||
float filterIIR(const float new_val, const float old_val, const float gain) const;
|
||||
void updatePacketLoss(On_Line_Node_S& node, const uint16_t recieved_packet);
|
||||
void processAPIRssi(const char* command_response);
|
||||
uint64_t get64BitsAddress(const char* bytes, const int offset);
|
||||
struct On_Line_Node_S
|
||||
{
|
||||
bool received_hole_packet_;
|
||||
std::string address_64_bits_;
|
||||
};
|
||||
|
||||
std::set<uint8_t> fragments_indexes_to_transmit_;
|
||||
SerialDevice* serial_device_;
|
||||
|
@ -173,27 +135,18 @@ namespace Xbee
|
|||
std::map<uint8_t, Reassembly_Packet_S>::iterator assembly_map_it_;
|
||||
std::map<uint64_t, uint8_t> database_addresses_;
|
||||
std::map<uint64_t, uint8_t>::iterator database_addresses_it_;
|
||||
std::map<uint8_t, uint64_t> database_addresses_inv_;
|
||||
std::map<uint8_t, uint64_t>::iterator database_addresses_inv_it_;
|
||||
std::map<uint8_t, On_Line_Node_S> packet_loss_map_;
|
||||
std::map<uint8_t, On_Line_Node_S>::iterator packet_loss_it_;
|
||||
std::map<uint8_t, RSSI_Result> rssi_result_map_;
|
||||
std::map<uint8_t, RSSI_Result>::iterator rssi_result_map_it_;
|
||||
|
||||
std::mutex mutex_;
|
||||
uint8_t device_address_;
|
||||
uint64_t local_64_bits_address_;
|
||||
std::string device_64_bits_address_;
|
||||
bool loaded_SL_;
|
||||
bool loaded_SH_;
|
||||
bool deque_full_;
|
||||
float rssi_float_;
|
||||
uint8_t current_processed_packet_ID_;
|
||||
std::size_t optimum_MT_NBR_;
|
||||
// TO DO & after auto !?
|
||||
useconds_t delay_interframes_;
|
||||
};
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -49,18 +49,11 @@ public:
|
|||
void Set_In_Messages_Pointers(Thread_Safe_Deque* in_std_messages,
|
||||
Thread_Safe_Deque* in_fragments,
|
||||
Thread_Safe_Deque* in_Acks_and_Pings,
|
||||
Thread_Safe_Deque* command_responses,
|
||||
Thread_Safe_Deque* in_packet_loss);
|
||||
Thread_Safe_Deque* command_responses);
|
||||
bool Is_IO_Service_Stopped(); // TO DO delete this function
|
||||
void Reset_IO_Service(); // TO DO delete this function
|
||||
void Close_Serial_Port();
|
||||
|
||||
const char FRAGMENT_MSG_ID = 'F';
|
||||
const char ACKNOWLEDGEMENT_MSG_ID = 'A';
|
||||
const char PING_MSG_ID = 'P';
|
||||
const char STANDARD_MSG_ID = 'S';
|
||||
const char PACKET_LOSS_MSG_ID = 'L';
|
||||
|
||||
private:
|
||||
|
||||
enum FRAME_TYPE
|
||||
|
@ -95,8 +88,6 @@ private:
|
|||
Thread_Safe_Deque* in_fragments_;
|
||||
Thread_Safe_Deque* in_Acks_and_Pings_;
|
||||
Thread_Safe_Deque* command_responses_;
|
||||
Thread_Safe_Deque* in_packet_loss_;
|
||||
|
||||
Mist::Xbee::Frame current_frame_;
|
||||
unsigned int FRAME_TYPE_KEYS[REMOTE_AT_COMMAND_RESPONSE + 1];
|
||||
};
|
||||
|
|
|
@ -1,14 +0,0 @@
|
|||
/* ----------------------------------------------------------------
|
||||
* File: XBeeSetup.cpp
|
||||
* Date: 02/06/2017
|
||||
* Author: Pierre-Yves Breches
|
||||
* Description: Implementation of the xbeeSetup function to
|
||||
* configure the xbee module
|
||||
* Copyright Humanitas Solutions. All rights reserved.
|
||||
------------------------------------------------------------------ */
|
||||
#include<thread>
|
||||
|
||||
#include"XBeeModule.h"
|
||||
#include"XMLConfigParser.h"
|
||||
|
||||
bool setupXBee(const std::string& device_port, const unsigned int baud_rate);
|
|
@ -1,59 +0,0 @@
|
|||
/* ----------------------------------------------------------------
|
||||
* File: frame_generators.h
|
||||
* Created on: 21/06/2017
|
||||
* Author: Pierre-Yves Breches
|
||||
* Description: This file contains functions used for the the creation of xbee
|
||||
* frame
|
||||
* Copyright Humanitas Solutions. All rights reserved.
|
||||
------------------------------------------------------------------ */
|
||||
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <inttypes.h>
|
||||
#include <iomanip>
|
||||
#include <sstream>
|
||||
|
||||
namespace Mist
|
||||
{
|
||||
|
||||
namespace Xbee
|
||||
{
|
||||
|
||||
void Generate_Transmit_Request_Frame(
|
||||
const char* message,
|
||||
std::string* frame,
|
||||
const std::size_t message_size,
|
||||
const unsigned char frame_ID = static_cast<unsigned char>(0x01),
|
||||
const std::string& destination_adssress = "000000000000FFFF",
|
||||
const std::string& short_destination_adress = "FFFF",
|
||||
const std::string& broadcast_radius = "00",
|
||||
const std::string& options = "00");
|
||||
|
||||
void generateLinkTestingFrame(
|
||||
std::string* frame,
|
||||
uint16_t rssi_payload_size,
|
||||
uint16_t rssi_iterations,
|
||||
std::string device_64_bits_address,
|
||||
uint64_t target_64_bits_address);
|
||||
|
||||
void Generate_AT_Command(const char* command,
|
||||
std::string* frame,
|
||||
const unsigned char frame_ID =
|
||||
static_cast<unsigned char>(0x01));
|
||||
|
||||
void Convert_HEX_To_Bytes(const std::string& HEX_data,
|
||||
std::string* converted_data);
|
||||
void Calculate_and_Append_Checksum(std::string* frame);
|
||||
void Add_Length_and_Start_Delimiter(std::string* frame);
|
||||
|
||||
template< typename T >
|
||||
std::string int_to_hex(const T i, int size)
|
||||
{
|
||||
std::stringstream stream;
|
||||
stream << std::setfill ('0') << std::setw(size)
|
||||
<< std::hex << i;
|
||||
return stream.str();
|
||||
}
|
||||
}
|
||||
|
||||
}
|
|
@ -1,20 +1,14 @@
|
|||
<launch>
|
||||
<arg name="port" default="/dev/ttyUSB0"/>
|
||||
<arg name="baud" default="9600"/>
|
||||
<!-- master / slave-->
|
||||
<arg name="drone" default="master"/>
|
||||
<!-- swarm / solo -->
|
||||
<arg name="mode" default="swarm"/>
|
||||
|
||||
<!-- xbee_mav Drone type and Commununication Mode -->
|
||||
<node pkg="xbee_ros_node" type="xbee_mav" name="xbee_mav" args="$(arg drone) $(arg mode)" output="screen" />
|
||||
|
||||
<!-- xbee_mav Topics and Services Names -->
|
||||
<!-- xmee_mav Drone type and Commununication Mode -->
|
||||
<!-- node pkg="xbee_ros_node" type="xbee_mav" name="xbee_mav" args="master solo" output="screen" -->
|
||||
<node pkg="xbee_ros_node" type="xbee_mav" name="xbee_mav" args="master swarm" output="screen" />
|
||||
<!-- node pkg="xbee_ros_node" type="xbee_mav" name="xbee_mav" args="slave solo" output="screen" -->
|
||||
<!--node pkg="xbee_ros_node" type="xbee_mav" name="xbee_mav" args="slave swarm" output="screen" -->
|
||||
<!-- xmee_mav Topics and Services Names -->
|
||||
<param name="Xbee_In_From_Buzz" type="str" value="outMavlink" />
|
||||
<param name="Xbee_Out_To_Buzz" type="str" value="inMavlink" />
|
||||
<param name="Xbee_In_From_Controller" type="str" value="xbee_cmd" />
|
||||
<param name="Xbee_Out_To_Controller" type="str" value="mav_dji_cmd" />
|
||||
<param name="USB_port" type="str" value="$(arg port)" />
|
||||
<param name="status_service" type="str" value="network_status" />
|
||||
<param name="Baud_rate" type="double" value="$(arg baud)" />
|
||||
<param name="USB_port" type="str" value="/dev/ttyUSB0" />
|
||||
<param name="Baud_rate" type="double" value="230400" />
|
||||
</launch>
|
||||
|
|
|
@ -1,27 +0,0 @@
|
|||
<launch>
|
||||
<group ns="receiver">
|
||||
<include file="$(find xbee_ros_node)/launch/xbeemav.launch" />
|
||||
<include file="$(find rosbuzz)/launch/rosbuzz.launch" >
|
||||
<arg name="xbee_plugged" value="true"/>
|
||||
<arg name="script" value="main"/>
|
||||
<arg name="setmode" value="true"/>
|
||||
<arg name="latitude" value="29.020237"/>
|
||||
<arg name="longitude" value="-13.710779"/>
|
||||
</include>
|
||||
</group>
|
||||
|
||||
<group ns="sender">
|
||||
<!-- node pkg="xbee_ros_node" type="test_buzz_cyclic" name="xbee_mav_test" output="screen" /-->
|
||||
<include file="$(find xbee_ros_node)/launch/xbeemav.launch">
|
||||
<arg name="port" default="/dev/ttyUSB1" />
|
||||
</include>
|
||||
|
||||
<include file="$(find rosbuzz)/launch/rosbuzz.launch" >
|
||||
<arg name="xbee_plugged" value="true"/>
|
||||
<arg name="script" value="main"/>
|
||||
<arg name="setmode" value="true"/>
|
||||
<arg name="latitude" value="29.020237"/>
|
||||
<arg name="longitude" value="-13.710779"/>
|
||||
</include>
|
||||
</group>
|
||||
</launch>
|
|
@ -4,29 +4,23 @@
|
|||
/* ------------------------------------------------------------------------- */
|
||||
/* September 20, 2016 -- @Copyright Aymen Soussia. All rights reserved. */
|
||||
/* (aymen.soussia@gmail.com) */
|
||||
/* ------------------------------------------------------------------------- */
|
||||
/* Revision
|
||||
* Date: July 1st, 2017
|
||||
* Author: Pierre-Yves Breches
|
||||
*/
|
||||
/* ------------------------------------------------------------------------- */
|
||||
|
||||
|
||||
#include "CommunicationManager.h"
|
||||
|
||||
|
||||
namespace Mist
|
||||
{
|
||||
|
||||
|
||||
namespace Xbee
|
||||
{
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
CommunicationManager::CommunicationManager():
|
||||
START_DLIMITER(static_cast<unsigned char>(0x7E)),
|
||||
LOOP_RATE(10), /* 10 fps */
|
||||
DEFAULT_RATE_DIVIDER_RSSI(5),
|
||||
DEFAULT_RATE_DIVIDER_PACKET_LOSS(20),
|
||||
DEFAULT_RSSI_PAYLOAD_SIZE(10),
|
||||
DEFAULT_RSSI_ITERATIONS(2)
|
||||
LOOP_RATE(10) /* 10 fps */
|
||||
{
|
||||
}
|
||||
|
||||
|
@ -38,14 +32,13 @@ CommunicationManager::~CommunicationManager()
|
|||
|
||||
|
||||
//*****************************************************************************
|
||||
bool CommunicationManager::Init(const std::string& device,
|
||||
const std::size_t baud_rate)
|
||||
bool CommunicationManager::Init(
|
||||
const std::string& device, const std::size_t baud_rate)
|
||||
{
|
||||
if (serial_device_.Init(device, baud_rate))
|
||||
{
|
||||
serial_device_.Set_In_Messages_Pointers(&in_std_messages_, &in_fragments_,
|
||||
&in_Acks_and_Pings_, &command_responses_,
|
||||
&in_packet_loss_);
|
||||
&in_Acks_and_Pings_, &command_responses_);
|
||||
|
||||
service_thread_ = std::make_shared<std::thread>(std::thread(&SerialDevice::Run_Service, &serial_device_));
|
||||
|
||||
|
@ -134,6 +127,7 @@ void CommunicationManager::Run_In_Solo_Mode(DRONE_TYPE drone_type)
|
|||
|
||||
while (ros::ok())
|
||||
{
|
||||
Check_In_Messages_and_Transfer_To_Server();
|
||||
ros::spinOnce();
|
||||
loop_rate.sleep();
|
||||
}
|
||||
|
@ -145,21 +139,39 @@ void CommunicationManager::Run_In_Solo_Mode(DRONE_TYPE drone_type)
|
|||
//*****************************************************************************
|
||||
void CommunicationManager::Run_In_Swarm_Mode()
|
||||
{
|
||||
std::string out_messages_topic;
|
||||
std::string in_messages_topic;
|
||||
bool success_1 = false;
|
||||
bool success_2 = false;
|
||||
StatusSrv_ = node_handle_.advertiseService("/xbee_status", &CommunicationManager::Get_Param, this);
|
||||
if (node_handle_.getParam("Xbee_In_From_Buzz", out_messages_topic))
|
||||
{
|
||||
mavlink_subscriber_ = node_handle_.subscribe(out_messages_topic.c_str(), 1000,
|
||||
&CommunicationManager::Send_Mavlink_Message_Callback, this);
|
||||
success_1 = true;
|
||||
}
|
||||
else
|
||||
std::cout << "Failed to Get Topic Name: param 'Xbee_In_From_Buzz' Not Found." << std::endl;
|
||||
|
||||
if (getRosParams())
|
||||
if (node_handle_.getParam("Xbee_Out_To_Buzz", in_messages_topic))
|
||||
{
|
||||
mavlink_publisher_ = node_handle_.advertise<mavros_msgs::Mavlink>(
|
||||
in_messages_topic.c_str(), 1000);
|
||||
success_2 = true;
|
||||
}
|
||||
else
|
||||
std::cout << "Failed to Get Topic Name: param 'Xbee_Out_To_Buzz' Not Found." << std::endl;
|
||||
|
||||
if (success_1 && success_2)
|
||||
{
|
||||
|
||||
ros::Rate loop_rate(LOOP_RATE);
|
||||
|
||||
while (ros::ok())
|
||||
{
|
||||
triggerRssiUpdate();
|
||||
Process_In_Standard_Messages();
|
||||
Process_In_Fragments();
|
||||
Process_In_Acks_and_Pings();
|
||||
Process_In_Packets();
|
||||
Process_Packet_Loss();
|
||||
Process_Command_Responses();
|
||||
packets_handler_.Delete_Packets_With_Time_Out();
|
||||
ros::spinOnce();
|
||||
loop_rate.sleep();
|
||||
|
@ -170,8 +182,61 @@ void CommunicationManager::Run_In_Swarm_Mode()
|
|||
|
||||
//*****************************************************************************
|
||||
inline bool CommunicationManager::Serve_Flight_Controller(mavros_msgs::CommandInt::
|
||||
Request& request, mavros_msgs::CommandInt::Response& response) // TODO to be cleaned
|
||||
Request& request, mavros_msgs::CommandInt::Response& response)
|
||||
{
|
||||
const std::size_t MAX_BUFFER_SIZE = 256;
|
||||
unsigned int command = 0;
|
||||
char temporary_buffer[MAX_BUFFER_SIZE];
|
||||
std::string frame;
|
||||
|
||||
/*switch(request.command)
|
||||
{
|
||||
case mavros_msgs::CommandCode::NAV_TAKEOFF:
|
||||
{
|
||||
command = static_cast<unsigned int>(mavros_msgs::CommandCode::NAV_TAKEOFF);
|
||||
sprintf(temporary_buffer, "%u ", command);
|
||||
response.success = true;
|
||||
break;
|
||||
}
|
||||
case mavros_msgs::CommandCode::NAV_LAND:
|
||||
{
|
||||
command = static_cast<unsigned int>(mavros_msgs::CommandCode::NAV_LAND);
|
||||
sprintf(temporary_buffer, "%u ", command);
|
||||
response.success = true;
|
||||
break;
|
||||
}
|
||||
case mavros_msgs::CommandCode::NAV_RETURN_TO_LAUNCH:
|
||||
{
|
||||
command = static_cast<unsigned int>(mavros_msgs::CommandCode::NAV_RETURN_TO_LAUNCH);
|
||||
sprintf(temporary_buffer, "%u ", command);
|
||||
response.success = true;
|
||||
break;
|
||||
}
|
||||
case mavros_msgs::CommandCode::NAV_WAYPOINT:
|
||||
{
|
||||
command = static_cast<unsigned int>(mavros_msgs::CommandCode::NAV_WAYPOINT);
|
||||
sprintf(temporary_buffer, "%u %u %u %lf %u %u ",
|
||||
command, request.x, request.y, request.z, 0, 1); // TO DO change 0 and 1
|
||||
response.success = true;
|
||||
break;
|
||||
}
|
||||
case mavros_msgs::CommandCode::CMD_MISSION_START:
|
||||
{
|
||||
command = static_cast<unsigned int>(mavros_msgs::CommandCode::CMD_MISSION_START);
|
||||
sprintf(temporary_buffer, "%u ", command);
|
||||
response.success = true;
|
||||
break;
|
||||
}
|
||||
default:
|
||||
response.success = false;
|
||||
}
|
||||
|
||||
if (command != 0)
|
||||
{
|
||||
Generate_Transmit_Request_Frame(temporary_buffer, &frame);
|
||||
serial_device_.Send_Frame(frame);
|
||||
}*/
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -190,10 +255,179 @@ void CommunicationManager::Display_Init_Communication_Failure()
|
|||
}
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
/*inline void CommunicationManager::Generate_Transmit_Request_Frame(
|
||||
const char* const message,
|
||||
std::string * frame,
|
||||
const unsigned char frame_ID,
|
||||
const std::string& destination_adssress,
|
||||
const std::string& short_destination_adress,
|
||||
const std::string& broadcast_radius,
|
||||
const std::string& options)
|
||||
{
|
||||
const unsigned char FAME_TYPE = static_cast<unsigned char>(0x10); /* Transmit Request Frame */
|
||||
/*std::string frame_parameters;
|
||||
std::string bytes_frame_parameters;
|
||||
|
||||
frame_parameters.append(destination_adssress);
|
||||
frame_parameters.append(short_destination_adress);
|
||||
frame_parameters.append(broadcast_radius);
|
||||
frame_parameters.append(options);
|
||||
|
||||
Convert_HEX_To_Bytes(frame_parameters, &bytes_frame_parameters);
|
||||
|
||||
frame->push_back(FAME_TYPE);
|
||||
frame->push_back(frame_ID);
|
||||
frame->append(bytes_frame_parameters);
|
||||
frame->append(message, std::strlen(message));
|
||||
|
||||
Calculate_and_Append_Checksum(frame);
|
||||
Add_Length_and_Start_Delimiter(frame);
|
||||
}*/
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
/*inline void CommunicationManager::Convert_HEX_To_Bytes(
|
||||
const std::string& HEX_data, std::string* converted_data)
|
||||
{
|
||||
const unsigned short TWO_BYTES = 2;
|
||||
char temporary_buffer[TWO_BYTES];
|
||||
unsigned char temporary_char;
|
||||
int temporary_HEX;
|
||||
|
||||
for (unsigned short i = 0; i <= HEX_data.size() - TWO_BYTES;
|
||||
i += TWO_BYTES)
|
||||
{
|
||||
memcpy(temporary_buffer, HEX_data.c_str() + i, TWO_BYTES);
|
||||
sscanf(temporary_buffer, "%02X", &temporary_HEX);
|
||||
temporary_char = static_cast<unsigned char>(temporary_HEX);
|
||||
converted_data->push_back(temporary_char);
|
||||
}
|
||||
}*/
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
/*inline void CommunicationManager::Calculate_and_Append_Checksum(
|
||||
std::string* frame)
|
||||
{
|
||||
unsigned short bytes_sum = 0;
|
||||
unsigned lowest_8_bits = 0;
|
||||
unsigned short checksum = 0;
|
||||
unsigned char checksum_byte;
|
||||
|
||||
for (unsigned short i = 0; i < frame->size(); i++)
|
||||
bytes_sum += static_cast<unsigned short>(frame->at(i));
|
||||
|
||||
lowest_8_bits = bytes_sum & 0xFF;
|
||||
checksum = 0xFF - lowest_8_bits;
|
||||
checksum_byte = static_cast<unsigned char>(checksum);
|
||||
frame->push_back(checksum_byte);
|
||||
}*/
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
/*inline void CommunicationManager::Add_Length_and_Start_Delimiter(
|
||||
std::string* frame)
|
||||
{
|
||||
const unsigned short FIVE_BYTES = 5;
|
||||
char temporary_buffer[FIVE_BYTES];
|
||||
unsigned char temporary_char;
|
||||
int Hex_frame_length_1;
|
||||
int Hex_frame_length_2;
|
||||
std::string header;
|
||||
int frame_length = frame->size() - 1; /* frame_length = frame_size - checksum byte */
|
||||
|
||||
/*header.push_back(START_DLIMITER);
|
||||
sprintf(temporary_buffer, "%04X", frame_length);
|
||||
sscanf(temporary_buffer, "%02X%02X", &Hex_frame_length_1,
|
||||
&Hex_frame_length_2);
|
||||
temporary_char = static_cast<unsigned char>(Hex_frame_length_1);
|
||||
header.push_back(temporary_char);
|
||||
temporary_char = static_cast<unsigned char>(Hex_frame_length_2);
|
||||
header.push_back(temporary_char);
|
||||
frame->insert(0, header);
|
||||
}*/
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
/*inline void CommunicationManager::Check_In_Messages_and_Transfer_To_Topics() // TO DO delete
|
||||
{
|
||||
std::size_t size_in_messages = in_messages_->Get_Size();
|
||||
|
||||
if (size_in_messages > 0)
|
||||
{
|
||||
uint64_t current_int64 = 0;
|
||||
|
||||
for (std::size_t j = 0; j < size_in_messages; j++)
|
||||
{
|
||||
std::shared_ptr<std::string> in_message =
|
||||
in_messages_->Pop_Front();
|
||||
mavros_msgs::Mavlink mavlink_msg;
|
||||
|
||||
for (std::size_t i = 0; i < in_message->size(); i++)
|
||||
{
|
||||
if (' ' == in_message->at(i) || 0 == i)
|
||||
{
|
||||
sscanf(in_message->c_str() + i, "%" PRIu64 " ",
|
||||
¤t_int64);
|
||||
mavlink_msg.payload64.push_back(current_int64);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
mavlink_publisher_.publish(mavlink_msg);
|
||||
}
|
||||
|
||||
}
|
||||
}*/
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
inline void CommunicationManager::Check_In_Messages_and_Transfer_To_Server() // TO DO change it
|
||||
{
|
||||
//std::size_t size_in_messages = in_messages_->Get_Size();
|
||||
|
||||
/*if (size_in_messages > 0)
|
||||
{
|
||||
for (std::size_t j = 0; j < size_in_messages; j++)
|
||||
{
|
||||
std::shared_ptr<std::string> in_message =
|
||||
in_messages_->Pop_Front();
|
||||
mavros_msgs:: CommandInt command_msg;
|
||||
unsigned int command = 0;
|
||||
|
||||
sscanf(in_message->c_str(), "%u", &command);
|
||||
|
||||
if (static_cast<unsigned int>(mavros_msgs::CommandCode::NAV_WAYPOINT) == command)
|
||||
{
|
||||
Waypoint_S new_waypoint;
|
||||
sscanf(in_message->c_str(), "%u %u %u %lf %u %u ",
|
||||
&command, &new_waypoint.latitude,
|
||||
&new_waypoint.longitude, &new_waypoint.altitude,
|
||||
&new_waypoint.staytime, &new_waypoint.heading);
|
||||
command_msg.request.x = new_waypoint.latitude;
|
||||
command_msg.request.y = new_waypoint.longitude;
|
||||
command_msg.request.z = new_waypoint.altitude;
|
||||
// TO DO add staytime and heading;
|
||||
}
|
||||
|
||||
command_msg.request.command = command;
|
||||
|
||||
if (mav_dji_client_.call(command_msg))
|
||||
ROS_INFO("XBeeMav: Command Successfully Tranferred to Dji Mav.");
|
||||
else
|
||||
ROS_INFO("XBeeMav: Faild to Tranfer Command.");
|
||||
|
||||
}
|
||||
}*/
|
||||
}
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
inline void CommunicationManager::Send_Mavlink_Message_Callback(
|
||||
const mavros_msgs::Mavlink::ConstPtr& mavlink_msg)
|
||||
{
|
||||
//std::cout << "Received Message From Buzz" << std::endl; // TO DO delete
|
||||
packets_handler_.Handle_Mavlink_Message(mavlink_msg);
|
||||
}
|
||||
|
||||
|
@ -272,8 +506,6 @@ void CommunicationManager::Process_In_Fragments()
|
|||
|
||||
//*****************************************************************************
|
||||
void CommunicationManager::Process_In_Packets()
|
||||
/* This function publish MAVROS msgs comming the xbee network.
|
||||
*/
|
||||
{
|
||||
std::size_t in_messages_size = in_packets_.Get_Size();
|
||||
|
||||
|
@ -294,9 +526,6 @@ void CommunicationManager::Process_In_Packets()
|
|||
|
||||
//*****************************************************************************
|
||||
void CommunicationManager::Process_Command_Responses()
|
||||
/* This function forwards the command responses to the packethandler to be
|
||||
* processed.
|
||||
*/
|
||||
{
|
||||
std::size_t in_messages_size = command_responses_.Get_Size();
|
||||
|
||||
|
@ -312,222 +541,21 @@ void CommunicationManager::Process_Command_Responses()
|
|||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
bool CommunicationManager::Get_Param (mavros_msgs::ParamGet::Request& req,
|
||||
mavros_msgs::ParamGet::Response& res)
|
||||
/* This function processes the requests sent to the xbee_status rosservice
|
||||
* The response success is set to true if the param_id of the request is known
|
||||
* Return: true
|
||||
*/
|
||||
//TODO these ids need to be defined as constants
|
||||
{
|
||||
bool CommunicationManager::Get_Param (mavros_msgs::ParamGet::Request& req, mavros_msgs::ParamGet::Response& res){
|
||||
mavros_msgs::ParamValue val;
|
||||
res.success = true;
|
||||
|
||||
if(req.param_id == "id")
|
||||
{
|
||||
val.integer=packets_handler_.getDeviceId();
|
||||
if(req.param_id=="id"){
|
||||
val.integer=packets_handler_.get_device_id();
|
||||
} else if(req.param_id=="rssi"){
|
||||
val.integer=-1;
|
||||
} else if(req.param_id=="pl"){
|
||||
val.integer=-1;
|
||||
}
|
||||
if(req.param_id == "deque_full")
|
||||
{
|
||||
val.integer=packets_handler_.getDequeFull();
|
||||
}
|
||||
/////////////////////////////////////////////////////////
|
||||
// RSSI Section
|
||||
else if(req.param_id == "rssi")
|
||||
{
|
||||
val.real=packets_handler_.getSignalStrength();
|
||||
}
|
||||
else if(req.param_id == "trig_rssi_api_avg")
|
||||
{
|
||||
if(packets_handler_.triggerAPIRssiUpdate(rssi_payload_size_,
|
||||
rssi_iterations_,
|
||||
PacketsHandler::ALL_IDS) == 0)
|
||||
{
|
||||
res.success = false;
|
||||
}
|
||||
}
|
||||
else if (safeSubStr(req.param_id, 14) == "trig_rssi_api_")
|
||||
{
|
||||
int short_id = std::strtol(req.param_id.substr(14).c_str(), NULL, 10);
|
||||
if(packets_handler_.triggerAPIRssiUpdate(rssi_payload_size_,
|
||||
rssi_iterations_,
|
||||
static_cast<uint8_t>(short_id)) == 0)
|
||||
{
|
||||
res.success = false;
|
||||
}
|
||||
}
|
||||
else if (req.param_id == "get_rssi_api_avg")
|
||||
{
|
||||
val.real = packets_handler_.getAPISignalStrength(PacketsHandler::ALL_IDS);
|
||||
if(val.real == 0){res.success = false;}
|
||||
}
|
||||
else if (safeSubStr(req.param_id, 13) == "get_rssi_api_")
|
||||
{
|
||||
int short_id = std::strtol(req.param_id.substr(13).c_str(), NULL, 10);
|
||||
val.integer = short_id;
|
||||
val.real = packets_handler_.getAPISignalStrength(static_cast<uint8_t>(short_id));
|
||||
if(val.real == 0){res.success = false;}
|
||||
}
|
||||
/////////////////////////////////////////////////////////
|
||||
// Packet loss Section
|
||||
else if (req.param_id == "pl_raw_avg")
|
||||
{
|
||||
val.real = packets_handler_.getRawPacketLoss(PacketsHandler::ALL_IDS);
|
||||
if(val.real == PacketsHandler::PACKET_LOSS_UNAVAILABLE){res.success = false;}
|
||||
}
|
||||
else if (safeSubStr(req.param_id, 7) == "pl_raw_")
|
||||
{
|
||||
int short_id = std::strtol(req.param_id.substr(7).c_str(), NULL, 10);
|
||||
val.integer = short_id;
|
||||
val.real = packets_handler_.getRawPacketLoss(static_cast<uint8_t>(short_id));
|
||||
if(val.real == PacketsHandler::PACKET_LOSS_UNAVAILABLE){res.success = false;}
|
||||
}
|
||||
else if (req.param_id == "pl_filtered_avg")
|
||||
{
|
||||
val.real = packets_handler_.getPacketLoss(PacketsHandler::ALL_IDS);
|
||||
if(val.real == PacketsHandler::PACKET_LOSS_UNAVAILABLE){res.success = false;}
|
||||
}
|
||||
else if (safeSubStr(req.param_id, 12) == "pl_filtered_")
|
||||
{
|
||||
int short_id = std::strtol(req.param_id.substr(12).c_str(), NULL, 10);
|
||||
val.integer = short_id;
|
||||
val.real = packets_handler_.getPacketLoss(static_cast<uint8_t>(short_id));
|
||||
if(val.real == PacketsHandler::PACKET_LOSS_UNAVAILABLE){res.success = false;}
|
||||
}
|
||||
else
|
||||
{
|
||||
res.success = false;
|
||||
}
|
||||
|
||||
res.value= val;
|
||||
res.success=true;
|
||||
return true;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
bool CommunicationManager::getRosParams()
|
||||
/* This function queries all the ROS parameters.
|
||||
* Return False if a mandatory parameter could not be queried.
|
||||
*/
|
||||
{
|
||||
std::string out_messages_topic;
|
||||
std::string in_messages_topic;
|
||||
bool success_get_param_in_topic = false;
|
||||
bool success_get_param_out_topic = false;
|
||||
|
||||
if (node_handle_.getParam("status_service", out_messages_topic))
|
||||
{
|
||||
StatusSrv_ = node_handle_.advertiseService(out_messages_topic.c_str(),
|
||||
&CommunicationManager::Get_Param, this);
|
||||
}
|
||||
else
|
||||
{
|
||||
std::cout << "Failed to Get Status Service Name: param 'status_service' Not Found." << std::endl;
|
||||
}
|
||||
|
||||
if (node_handle_.getParam("Xbee_In_From_Buzz", out_messages_topic))
|
||||
{
|
||||
mavlink_subscriber_ = node_handle_.subscribe(out_messages_topic.c_str(), 100,
|
||||
&CommunicationManager::Send_Mavlink_Message_Callback, this);
|
||||
success_get_param_in_topic = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
std::cout << "Failed to Get Topic Name: param 'Xbee_In_From_Buzz' Not Found." << std::endl;
|
||||
}
|
||||
|
||||
if (node_handle_.getParam("Xbee_Out_To_Buzz", in_messages_topic))
|
||||
{
|
||||
mavlink_publisher_ = node_handle_.advertise<mavros_msgs::Mavlink>(
|
||||
in_messages_topic.c_str(), 100);
|
||||
success_get_param_out_topic = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
std::cout << "Failed to Get Topic Name: param 'Xbee_Out_To_Buzz' Not Found." << std::endl;
|
||||
}
|
||||
|
||||
rate_divider_rssi_ = static_cast<uint8_t>(getIntParam("rate_divider_rssi", DEFAULT_RSSI_ITERATIONS));
|
||||
rate_divider_packet_loss_ = static_cast<uint8_t>(getIntParam("rate_divider_packet_loss_", DEFAULT_RSSI_ITERATIONS));
|
||||
rssi_payload_size_ = static_cast<uint16_t>(getIntParam("rssi_payload_size", DEFAULT_RSSI_ITERATIONS));
|
||||
rssi_iterations_ = static_cast<uint16_t>(getIntParam("rssi_iterations", DEFAULT_RSSI_ITERATIONS));
|
||||
|
||||
return success_get_param_in_topic && success_get_param_out_topic;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
int CommunicationManager::getIntParam(std::string name, int default_value)
|
||||
{
|
||||
int temp_param;
|
||||
if(node_handle_.getParam(name, temp_param))
|
||||
{
|
||||
return temp_param;
|
||||
}
|
||||
else
|
||||
{
|
||||
return default_value;
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
void CommunicationManager::triggerRssiUpdate()
|
||||
{
|
||||
/* This trigger the update of the rssi parameter (Signal strength) every
|
||||
* rate_divider_rssi_ cycles
|
||||
*/
|
||||
static uint8_t rssi_update_count = 0;
|
||||
|
||||
rssi_update_count++;
|
||||
if(rssi_update_count >= rate_divider_rssi_){
|
||||
packets_handler_.triggerRssiUpdate();
|
||||
rssi_update_count = 0;
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
void CommunicationManager::Process_Packet_Loss()
|
||||
{
|
||||
/* This function passes the packet loss messages to the packethandler to be
|
||||
* processed.
|
||||
* It also sends the packet loss messages to the other every
|
||||
* rate_divider_packet_loss_ cycles
|
||||
*/
|
||||
std::size_t in_messages_size = in_packet_loss_.Get_Size();
|
||||
|
||||
if (in_messages_size > 0)
|
||||
{
|
||||
for (std::size_t j = 0; j < in_messages_size; j++)
|
||||
{
|
||||
std::shared_ptr<std::string> in_message =
|
||||
in_packet_loss_.Pop_Front();
|
||||
|
||||
packets_handler_.processPacketLoss(in_message->c_str());
|
||||
}
|
||||
}
|
||||
|
||||
packet_loss_timer_++;
|
||||
if (packet_loss_timer_ > rate_divider_packet_loss_)
|
||||
{
|
||||
packets_handler_.sendPacketLoss();
|
||||
packet_loss_timer_ = 0;
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
std::string CommunicationManager::safeSubStr(const std::string strg,
|
||||
const unsigned int index_max) const
|
||||
/* Verify if the operation substr(0, index_max) is possible on the given string
|
||||
* and return the substring if successful.
|
||||
* Error value: empty string;
|
||||
*/
|
||||
{
|
||||
if(strg.size() > index_max) {
|
||||
return strg.substr(0,index_max);
|
||||
}
|
||||
return std::string("");
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -4,17 +4,6 @@
|
|||
/* ------------------------------------------------------------------------- */
|
||||
/* February 06, 2017 -- @Copyright Aymen Soussia. All rights reserved. */
|
||||
/* (aymen.soussia@gmail.com) */
|
||||
/* Revision
|
||||
* Date: July 1st, 2017
|
||||
* Author: Pierre-Yves Breches
|
||||
*/
|
||||
/* ------------------------------------------------------------------------- */
|
||||
/* TODO
|
||||
* * Split PacketsHandler class (the last two could be instantiated by the first one)
|
||||
* * class PacketsHandler
|
||||
* * class PacketsLossHandler
|
||||
* * class APIRssiHandler
|
||||
*/
|
||||
|
||||
|
||||
#include"PacketsHandler.h"
|
||||
|
@ -27,25 +16,17 @@ namespace Mist
|
|||
namespace Xbee
|
||||
{
|
||||
|
||||
const uint8_t PacketsHandler::ALL_IDS = 0xFF;
|
||||
const uint16_t PacketsHandler::PACKET_LOSS_UNAVAILABLE = 0xFFFF;
|
||||
const uint8_t PacketsHandler::MAX_WAITING_OUT_MSG = 10;
|
||||
|
||||
//*****************************************************************************
|
||||
PacketsHandler::PacketsHandler():
|
||||
MAX_PACEKT_SIZE(64000),
|
||||
XBEE_NETWORK_MTU(250),
|
||||
FRAGMENT_HEADER_SIZE(6),
|
||||
MAX_TIME_TO_SEND_PACKET(30000), // TO DO change it to packet time out
|
||||
RSSI_COMMAND("DB"),
|
||||
RSSI_FILTER_GAIN(0.5),
|
||||
PACKET_LOSS_IDENTIFIER("L"),
|
||||
MAX_PACKET_LOSS_MSG_ID(100),
|
||||
PACKET_LOSS_FILTER_GAIN(0.7),
|
||||
MAX_TIME_TO_SEND_PACKET(30000),
|
||||
START_DLIMITER(static_cast<unsigned char>(0x7E)),
|
||||
device_64_bits_address_("12345678"),
|
||||
loaded_SL_(false),
|
||||
loaded_SH_(false),
|
||||
rssi_float_(0),
|
||||
optimum_MT_NBR_(3),
|
||||
delay_interframes_(100 * 1000)
|
||||
{
|
||||
|
@ -67,8 +48,6 @@ bool PacketsHandler::Init(SerialDevice* serial_device,
|
|||
if (!Load_Database_Addresses())
|
||||
return false;
|
||||
|
||||
// TO DO node dicov
|
||||
|
||||
Send_SL_and_SH_Commands();
|
||||
in_packets_ = in_packets;
|
||||
|
||||
|
@ -125,8 +104,8 @@ void PacketsHandler::Handle_Mavlink_Message(const mavros_msgs::Mavlink::ConstPtr
|
|||
fragmented_packet->at(i)->append(serialized_packet->c_str() + offset, NBR_of_bytes);
|
||||
offset += NBR_of_bytes;
|
||||
}
|
||||
out_packets_.Push_Back({static_cast<uint8_t>(mavlink_msg->msgid & 0xFF),
|
||||
fragmented_packet});
|
||||
|
||||
out_packets_.Push_Back({mavlink_msg->msgid, fragmented_packet});
|
||||
}
|
||||
else if (serialized_packet->size() < XBEE_NETWORK_MTU)
|
||||
{
|
||||
|
@ -147,10 +126,6 @@ void PacketsHandler::Process_Fragment(std::shared_ptr<std::string> fragment)
|
|||
static_cast<uint16_t>(static_cast<unsigned char>(fragment->at(5))));
|
||||
|
||||
assembly_map_it_ = packets_assembly_map_.find(node_8_bits_address);
|
||||
packet_loss_it_ = packet_loss_map_.find(node_8_bits_address);
|
||||
|
||||
if (packet_loss_it_ != packet_loss_map_.end())
|
||||
packet_loss_it_->second.received_packets_ = packet_loss_it_->second.received_packets_ + 1;
|
||||
|
||||
if (assembly_map_it_ != packets_assembly_map_.end())
|
||||
{
|
||||
|
@ -189,7 +164,7 @@ void PacketsHandler::Process_Fragment(std::shared_ptr<std::string> fragment)
|
|||
|
||||
|
||||
//*****************************************************************************
|
||||
void PacketsHandler::Insert_Fragment_In_Packet_Buffer(std::string* buffer, const char* fragment, const uint16_t offset, const std::size_t length) // TO DO delete length
|
||||
void PacketsHandler::Insert_Fragment_In_Packet_Buffer(std::string* buffer, const char* fragment, const uint16_t offset, const std::size_t length)
|
||||
{
|
||||
if (offset >= buffer->size())
|
||||
buffer->append(fragment + FRAGMENT_HEADER_SIZE, length - FRAGMENT_HEADER_SIZE);
|
||||
|
@ -199,7 +174,7 @@ void PacketsHandler::Insert_Fragment_In_Packet_Buffer(std::string* buffer, const
|
|||
|
||||
|
||||
//*****************************************************************************
|
||||
void PacketsHandler::Process_Ping_Or_Acknowledgement(std::shared_ptr<std::string> frame) // TO DO change useless std::shared_ptr<std::string> frame args to ->c_str()
|
||||
void PacketsHandler::Process_Ping_Or_Acknowledgement(std::shared_ptr<std::string> frame)
|
||||
{
|
||||
uint8_t packet_ID = frame->at(12);
|
||||
uint8_t node_8_bits_address = frame->at(13);
|
||||
|
@ -252,7 +227,6 @@ void PacketsHandler::Process_Ping_Or_Acknowledgement(std::shared_ptr<std::string
|
|||
|
||||
if (assembly_map_it_->second.received_fragments_IDs_.size() == packet_size)
|
||||
{
|
||||
// TO DO add test if the packet was already transmitted to rosbuzz dont transmit ack only if
|
||||
in_packets_->Push_Back(std::make_shared<std::string>(assembly_map_it_->second.packet_buffer_));
|
||||
assembly_map_it_->second.packet_buffer_.clear();
|
||||
assembly_map_it_->second.received_fragments_IDs_.clear();
|
||||
|
@ -308,9 +282,17 @@ void PacketsHandler::Process_Command_Response(const char* command_response)
|
|||
uint64_t new_node_address = 0;
|
||||
std::lock_guard<std::mutex> guard(mutex_);
|
||||
|
||||
if (command_response[2] == static_cast<unsigned char>(0)) // TO DO check this
|
||||
if (command_response[2] == static_cast<unsigned char>(0))
|
||||
{
|
||||
new_node_address = get64BitsAddress(command_response, 5);
|
||||
new_node_address = static_cast<uint64_t>(
|
||||
static_cast<unsigned char>(command_response[5]) << 56 |
|
||||
static_cast<unsigned char>(command_response[6]) << 48 |
|
||||
static_cast<unsigned char>(command_response[7]) << 40 |
|
||||
static_cast<unsigned char>(command_response[8]) << 32 |
|
||||
static_cast<unsigned char>(command_response[9]) << 24 |
|
||||
static_cast<unsigned char>(command_response[10]) << 16 |
|
||||
static_cast<unsigned char>(command_response[11]) << 8 |
|
||||
static_cast<unsigned char>(command_response[12]));
|
||||
}
|
||||
|
||||
database_addresses_it_ = database_addresses_.find(new_node_address);
|
||||
|
@ -340,63 +322,8 @@ void PacketsHandler::Process_Command_Response(const char* command_response)
|
|||
device_64_bits_address_[4 + i] = command_response[3 + i];
|
||||
}
|
||||
}
|
||||
else if (command_response[0] == 'D' && command_response[1] == 'B')
|
||||
{
|
||||
// TODO implemetation of a handler for error value responses (outside valid range)
|
||||
rssi_float_ = filterIIR(static_cast<float>(static_cast<uint16_t>(command_response[3])),
|
||||
rssi_float_,
|
||||
RSSI_FILTER_GAIN);
|
||||
}
|
||||
else if (command_response[0] == 'R' && command_response[1] == 'S')
|
||||
{
|
||||
processAPIRssi(command_response);
|
||||
}
|
||||
else
|
||||
{
|
||||
// nothing to do
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
void PacketsHandler::processAPIRssi(const char* command_response)
|
||||
{
|
||||
uint64_t node_address = get64BitsAddress(command_response, 2);
|
||||
|
||||
database_addresses_it_ = database_addresses_.find(node_address);
|
||||
if (database_addresses_it_ != database_addresses_.end())
|
||||
{
|
||||
rssi_result_map_it_ = rssi_result_map_.find(database_addresses_it_->second);
|
||||
if(rssi_result_map_it_ == rssi_result_map_.end())
|
||||
{
|
||||
RSSI_Result result ={ucharToUint16(command_response[10], command_response[11]),
|
||||
ucharToUint16(command_response[12], command_response[13]),
|
||||
ucharToUint16(command_response[14], command_response[15]),
|
||||
ucharToUint16(command_response[16], command_response[17]),
|
||||
static_cast<uint8_t>(command_response[18]),
|
||||
static_cast<uint8_t>(command_response[19]),
|
||||
static_cast<uint8_t>(command_response[20]),
|
||||
static_cast<uint8_t>(command_response[21]),
|
||||
static_cast<uint8_t>(command_response[22]),
|
||||
NEW_VALUE
|
||||
};
|
||||
rssi_result_map_[database_addresses_it_->second] = result;
|
||||
}
|
||||
else
|
||||
{
|
||||
rssi_result_map_it_->second.payload_size = ucharToUint16(command_response[10], command_response[11]);
|
||||
rssi_result_map_it_->second.iterations = ucharToUint16(command_response[12], command_response[13]);
|
||||
rssi_result_map_it_->second.success = ucharToUint16(command_response[14], command_response[15]);
|
||||
rssi_result_map_it_->second.retries = ucharToUint16(command_response[16], command_response[17]);
|
||||
rssi_result_map_it_->second.result = static_cast<uint8_t>(command_response[18]);
|
||||
rssi_result_map_it_->second.rr = static_cast<uint8_t>(command_response[19]);
|
||||
rssi_result_map_it_->second.max_rssi = static_cast<uint8_t>(command_response[20]);
|
||||
rssi_result_map_it_->second.min_rssi = static_cast<uint8_t>(command_response[21]);
|
||||
rssi_result_map_it_->second.avg_rssi = static_cast<uint8_t>(command_response[22]);
|
||||
rssi_result_map_it_->second.status = NEW_VALUE;
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
void PacketsHandler::Quit()
|
||||
|
@ -427,9 +354,9 @@ void PacketsHandler::Serialize_Mavlink_Message(const mavros_msgs::Mavlink::Const
|
|||
//*****************************************************************************
|
||||
void PacketsHandler::Insert_Fragment_Header(bool single_fragment,
|
||||
std::shared_ptr<std::string> fragment, const uint8_t packet_ID,
|
||||
const uint8_t fragment_ID, const uint16_t offset) // TO DO change this function
|
||||
const uint8_t fragment_ID, const uint16_t offset)
|
||||
{
|
||||
if (!single_fragment) // TO DO delete
|
||||
if (!single_fragment)
|
||||
{
|
||||
fragment->push_back('F');
|
||||
fragment->push_back(packet_ID);
|
||||
|
@ -438,8 +365,8 @@ void PacketsHandler::Insert_Fragment_Header(bool single_fragment,
|
|||
fragment->push_back(offset >> (1 * 8));
|
||||
fragment->push_back(offset >> (0 * 8));
|
||||
}
|
||||
else // TO DO delete
|
||||
fragment->push_back('S'); // TO DO delete
|
||||
else
|
||||
fragment->push_back('S');
|
||||
}
|
||||
|
||||
|
||||
|
@ -463,9 +390,6 @@ void PacketsHandler::Process_Out_Standard_Messages()
|
|||
{
|
||||
std::string frame;
|
||||
std::shared_ptr<std::string> out_message;
|
||||
if(deque_size > MAX_WAITING_OUT_MSG){deque_full_ = true;}
|
||||
else{deque_full_ = false;}
|
||||
|
||||
|
||||
for (std::size_t i = 0; i < deque_size; i++)
|
||||
{
|
||||
|
@ -474,12 +398,6 @@ void PacketsHandler::Process_Out_Standard_Messages()
|
|||
|
||||
Generate_Transmit_Request_Frame(out_message->c_str(), &frame, out_message->size());
|
||||
serial_device_->Send_Frame(frame);
|
||||
|
||||
for (auto& it:packet_loss_map_)
|
||||
{
|
||||
it.second.sent_packets_ = it.second.sent_packets_ + 1;
|
||||
}
|
||||
|
||||
usleep(delay_interframes_);
|
||||
}
|
||||
}
|
||||
|
@ -520,14 +438,9 @@ void PacketsHandler::Send_Packet(const Out_Packet_S& packet)
|
|||
while (std::clock() - start_time <= MAX_TIME_TO_SEND_PACKET && !Check_Packet_Transmitted_To_All_Nodes())
|
||||
{
|
||||
NBR_of_transmission++;
|
||||
|
||||
Transmit_Fragments(frames);
|
||||
|
||||
// TO DO usleep(flow_control_time)
|
||||
// TO DO clear fragments_IDs_to_transmit_set
|
||||
Send_End_Of_Packet_Ping(packet.packet_ID_, packet.packet_buffer_->size());
|
||||
usleep(500 * 1000);
|
||||
// TO DO sleep after ping
|
||||
}
|
||||
|
||||
Adjust_Optimum_MT_Number(std::clock() - start_time, NBR_of_transmission);
|
||||
|
@ -618,7 +531,6 @@ bool PacketsHandler::Get_Local_Address()
|
|||
if (database_addresses_it_ != database_addresses_.end())
|
||||
{
|
||||
device_address_ = database_addresses_it_->second;
|
||||
local_64_bits_address_ = local_64_bits_address;
|
||||
std::cout << "Loaded Short Device Address : " << static_cast<int>(device_address_) << std::endl;
|
||||
return true;
|
||||
}
|
||||
|
@ -655,9 +567,7 @@ bool PacketsHandler::Check_Packet_Transmitted_To_All_Nodes()
|
|||
|
||||
|
||||
//*****************************************************************************
|
||||
void PacketsHandler::Init_Network_Nodes_For_New_Transmission(const uint8_t packet_ID,
|
||||
std::vector<std::string>* frames,
|
||||
std::shared_ptr<std::vector<std::shared_ptr<std::string>>> packet)
|
||||
void PacketsHandler::Init_Network_Nodes_For_New_Transmission(const uint8_t packet_ID, std::vector<std::string>* frames, std::shared_ptr<std::vector<std::shared_ptr<std::string>>> packet)
|
||||
{
|
||||
std::lock_guard<std::mutex> guard(mutex_);
|
||||
fragments_indexes_to_transmit_.clear();
|
||||
|
@ -684,11 +594,6 @@ void PacketsHandler::Transmit_Fragments(const std::vector<std::string>& frames)
|
|||
for (auto index: fragments_indexes_to_transmit_)
|
||||
{
|
||||
serial_device_->Send_Frame(frames.at(index));
|
||||
for (auto& it:packet_loss_map_)
|
||||
{
|
||||
it.second.sent_packets_ = it.second.sent_packets_ + 1;
|
||||
}
|
||||
|
||||
usleep(delay_interframes_);
|
||||
}
|
||||
|
||||
|
@ -734,366 +639,136 @@ void PacketsHandler::Deserialize_Mavlink_Message(const char * bytes,
|
|||
|
||||
for (std::size_t i = 2; i < msg_size; i += 8)
|
||||
{
|
||||
current_int64 = get64BitsAddress(bytes, i);
|
||||
current_int64 = (
|
||||
static_cast<uint64_t>(static_cast<unsigned char>(bytes[i])) << 56 |
|
||||
static_cast<uint64_t>(static_cast<unsigned char>(bytes[i + 1])) << 48 |
|
||||
static_cast<uint64_t>(static_cast<unsigned char>(bytes[i + 2])) << 40 |
|
||||
static_cast<uint64_t>(static_cast<unsigned char>(bytes[i + 3])) << 32 |
|
||||
static_cast<uint64_t>(static_cast<unsigned char>(bytes[i + 4])) << 24 |
|
||||
static_cast<uint64_t>(static_cast<unsigned char>(bytes[i + 5])) << 16 |
|
||||
static_cast<uint64_t>(static_cast<unsigned char>(bytes[i + 6])) << 8 |
|
||||
static_cast<uint64_t>(static_cast<unsigned char>(bytes[i + 7])));
|
||||
|
||||
mavlink_msg->payload64.push_back(current_int64);
|
||||
}
|
||||
}
|
||||
|
||||
packet_loss_it_ = packet_loss_map_.find(mavlink_msg->sysid);
|
||||
|
||||
if (packet_loss_it_ != packet_loss_map_.end())
|
||||
{
|
||||
packet_loss_it_->second.received_packets_ = packet_loss_it_->second.received_packets_ + 1;
|
||||
}
|
||||
else
|
||||
{
|
||||
database_addresses_inv_it_ = database_addresses_inv_.find(mavlink_msg->sysid);
|
||||
if (database_addresses_inv_it_ != database_addresses_inv_.end())
|
||||
{
|
||||
uint64_t long_address = database_addresses_inv_it_->second;
|
||||
packet_loss_map_.insert(std::pair<uint8_t, On_Line_Node_S>(mavlink_msg->sysid,
|
||||
{long_address, 0.0, 0.0, 0, 0, 0, 0}));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
uint8_t PacketsHandler::getDeviceId(){
|
||||
inline void PacketsHandler::Generate_Transmit_Request_Frame(
|
||||
const char* message,
|
||||
std::string * frame,
|
||||
const std::size_t message_size,
|
||||
const unsigned char frame_ID,
|
||||
const std::string& destination_adssress,
|
||||
const std::string& short_destination_adress,
|
||||
const std::string& broadcast_radius,
|
||||
const std::string& options)
|
||||
{
|
||||
const unsigned char FAME_TYPE = static_cast<unsigned char>(0x10); /* Transmit Request Frame */
|
||||
std::string frame_parameters;
|
||||
std::string bytes_frame_parameters;
|
||||
|
||||
frame_parameters.append(destination_adssress);
|
||||
frame_parameters.append(short_destination_adress);
|
||||
frame_parameters.append(broadcast_radius);
|
||||
frame_parameters.append(options);
|
||||
|
||||
Convert_HEX_To_Bytes(frame_parameters, &bytes_frame_parameters);
|
||||
|
||||
frame->push_back(FAME_TYPE);
|
||||
frame->push_back(frame_ID);
|
||||
frame->append(bytes_frame_parameters);
|
||||
frame->append(message, message_size);
|
||||
|
||||
Calculate_and_Append_Checksum(frame);
|
||||
Add_Length_and_Start_Delimiter(frame);
|
||||
}
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
inline void PacketsHandler::Add_Length_and_Start_Delimiter(
|
||||
std::string* frame)
|
||||
{
|
||||
const unsigned short FIVE_BYTES = 5;
|
||||
char temporary_buffer[FIVE_BYTES];
|
||||
unsigned char temporary_char;
|
||||
int Hex_frame_length_1;
|
||||
int Hex_frame_length_2;
|
||||
std::string header;
|
||||
int frame_length = frame->size() - 1; /* frame_length = frame_size - checksum byte */
|
||||
|
||||
header.push_back(START_DLIMITER);
|
||||
sprintf(temporary_buffer, "%04X", frame_length);
|
||||
sscanf(temporary_buffer, "%02X%02X", &Hex_frame_length_1,
|
||||
&Hex_frame_length_2);
|
||||
temporary_char = static_cast<unsigned char>(Hex_frame_length_1);
|
||||
header.push_back(temporary_char);
|
||||
temporary_char = static_cast<unsigned char>(Hex_frame_length_2);
|
||||
header.push_back(temporary_char);
|
||||
frame->insert(0, header);
|
||||
}
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
inline void PacketsHandler::Calculate_and_Append_Checksum(
|
||||
std::string* frame)
|
||||
{
|
||||
unsigned short bytes_sum = 0;
|
||||
unsigned lowest_8_bits = 0;
|
||||
unsigned short checksum = 0;
|
||||
unsigned char checksum_byte;
|
||||
|
||||
for (unsigned short i = 0; i < frame->size(); i++)
|
||||
bytes_sum += static_cast<unsigned short>(frame->at(i));
|
||||
|
||||
lowest_8_bits = bytes_sum & 0xFF;
|
||||
checksum = 0xFF - lowest_8_bits;
|
||||
checksum_byte = static_cast<unsigned char>(checksum);
|
||||
frame->push_back(checksum_byte);
|
||||
}
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
inline void PacketsHandler::Convert_HEX_To_Bytes(
|
||||
const std::string& HEX_data, std::string* converted_data)
|
||||
{
|
||||
const unsigned short TWO_BYTES = 2;
|
||||
char temporary_buffer[TWO_BYTES];
|
||||
unsigned char temporary_char;
|
||||
int temporary_HEX;
|
||||
|
||||
for (unsigned short i = 0; i <= HEX_data.size() - TWO_BYTES;
|
||||
i += TWO_BYTES)
|
||||
{
|
||||
memcpy(temporary_buffer, HEX_data.c_str() + i, TWO_BYTES);
|
||||
sscanf(temporary_buffer, "%02X", &temporary_HEX);
|
||||
temporary_char = static_cast<unsigned char>(temporary_HEX);
|
||||
converted_data->push_back(temporary_char);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
void PacketsHandler::Generate_AT_Command(const char* command,
|
||||
std::string* frame,
|
||||
const unsigned char frame_ID)
|
||||
{
|
||||
const unsigned char FAME_TYPE = static_cast<unsigned char>(0x09);/* AT Command Frame */
|
||||
std::string temporary_parameter_value;
|
||||
|
||||
frame->push_back(FAME_TYPE);
|
||||
frame->push_back(frame_ID);
|
||||
frame->append(command);
|
||||
|
||||
Calculate_and_Append_Checksum(frame);
|
||||
Add_Length_and_Start_Delimiter(frame);
|
||||
}
|
||||
|
||||
uint8_t PacketsHandler::get_device_id(){
|
||||
return device_address_;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
uint8_t PacketsHandler::getDequeFull(){
|
||||
if(deque_full_) {return 1;}
|
||||
else {return 0;}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
float PacketsHandler::getSignalStrength()
|
||||
{
|
||||
return rssi_float_;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
float PacketsHandler::getAPISignalStrength(uint8_t short_node_id)
|
||||
{
|
||||
float result = 0;
|
||||
int nb_node = 0;
|
||||
if(short_node_id == ALL_IDS)
|
||||
{
|
||||
for (auto& it:rssi_result_map_)
|
||||
{
|
||||
if(it.second.status == NEW_VALUE &&
|
||||
it.second.result == 0x00)
|
||||
{
|
||||
nb_node++;
|
||||
result += static_cast<float>(it.second.avg_rssi);
|
||||
it.second.status = OLD_VALUE;
|
||||
}
|
||||
}
|
||||
if(nb_node != 0)
|
||||
{
|
||||
result = static_cast<float>(result / nb_node);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
rssi_result_map_it_ = rssi_result_map_.find(short_node_id);
|
||||
if(rssi_result_map_it_ != rssi_result_map_.end())
|
||||
{
|
||||
if(rssi_result_map_it_->second.status == NEW_VALUE &&
|
||||
rssi_result_map_it_->second.result == 0x00)
|
||||
{
|
||||
result = static_cast<float>(rssi_result_map_it_->second.avg_rssi);
|
||||
rssi_result_map_it_->second.status = OLD_VALUE;
|
||||
}
|
||||
}
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
float PacketsHandler::getRawPacketLoss(uint8_t short_node_id)
|
||||
{
|
||||
if(short_node_id == ALL_IDS)
|
||||
{
|
||||
int count = 0;
|
||||
float result = 0;
|
||||
for(const auto& it:packet_loss_map_)
|
||||
{
|
||||
result += it.second.packet_loss_raw_;
|
||||
count++;
|
||||
}
|
||||
if(count != 0)
|
||||
{
|
||||
return result / static_cast<float>(count);
|
||||
}
|
||||
else {return PACKET_LOSS_UNAVAILABLE;}
|
||||
}
|
||||
else
|
||||
{
|
||||
packet_loss_it_ = packet_loss_map_.find(short_node_id);
|
||||
|
||||
if (packet_loss_it_ != packet_loss_map_.end())
|
||||
{
|
||||
return packet_loss_map_[short_node_id].packet_loss_raw_;
|
||||
}
|
||||
else {return PACKET_LOSS_UNAVAILABLE;}
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
float PacketsHandler::getPacketLoss(uint8_t short_node_id)
|
||||
{
|
||||
if(short_node_id == ALL_IDS)
|
||||
{
|
||||
int count = 0;
|
||||
float result = 0;
|
||||
for(const auto& it:packet_loss_map_)
|
||||
{
|
||||
result += it.second.packet_loss_filtered_;
|
||||
count++;
|
||||
}
|
||||
if(count != 0)
|
||||
{
|
||||
return result / static_cast<float>(count);
|
||||
}
|
||||
else {return PACKET_LOSS_UNAVAILABLE;}
|
||||
}
|
||||
else
|
||||
{
|
||||
packet_loss_it_ = packet_loss_map_.find(short_node_id);
|
||||
|
||||
if (packet_loss_it_ != packet_loss_map_.end())
|
||||
{
|
||||
return packet_loss_map_[short_node_id].packet_loss_filtered_;
|
||||
}
|
||||
else {return PACKET_LOSS_UNAVAILABLE;}
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
void PacketsHandler::triggerRssiUpdate()
|
||||
/* Description: function sending the AT commad DB to the Xbee module.
|
||||
*
|
||||
------------------------------------------------------------------ */
|
||||
{
|
||||
std::string frame;
|
||||
Generate_AT_Command(RSSI_COMMAND.c_str(), &frame);
|
||||
serial_device_->Send_Frame(frame);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
uint8_t PacketsHandler::triggerAPIRssiUpdate(uint16_t rssi_payload_size,
|
||||
uint16_t rssi_iterations,
|
||||
uint8_t target_id)
|
||||
/* Description: Function triggering the link testing function described
|
||||
* pages 29-30 in Ressources/XbeeModule_Datasheet.pdf
|
||||
* The packet_loss_map_ is used to know which nodes are connected
|
||||
* instead of the connected_network_nodes_ since the latest is only
|
||||
* updated when a Ping is sent.
|
||||
------------------------------------------------------------------ */
|
||||
{
|
||||
uint8_t sent_request = 0;
|
||||
|
||||
if(target_id == ALL_IDS)
|
||||
{
|
||||
for (const auto& it:packet_loss_map_)
|
||||
{
|
||||
std::string frame;
|
||||
generateLinkTestingFrame(&frame, rssi_payload_size,
|
||||
rssi_iterations,
|
||||
device_64_bits_address_,
|
||||
database_addresses_inv_[it.first]);
|
||||
serial_device_->Send_Frame(frame);
|
||||
sent_request++;
|
||||
|
||||
rssi_result_map_it_ = rssi_result_map_.find(it.first);
|
||||
if(rssi_result_map_it_ == rssi_result_map_.end())
|
||||
{
|
||||
RSSI_Result result ={rssi_payload_size, rssi_iterations, 0, 0, 0,
|
||||
0, 0, 0, 0, TRIGGERED};
|
||||
rssi_result_map_[database_addresses_it_->second] = result;
|
||||
}
|
||||
else
|
||||
{
|
||||
rssi_result_map_it_->second.payload_size = rssi_payload_size;
|
||||
rssi_result_map_it_->second.iterations = rssi_iterations;
|
||||
rssi_result_map_it_->second.avg_rssi = TRIGGERED;
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
packet_loss_it_ = packet_loss_map_.find(target_id);
|
||||
if(packet_loss_it_ != packet_loss_map_.end())
|
||||
{
|
||||
std::string frame;
|
||||
generateLinkTestingFrame(&frame, rssi_payload_size,
|
||||
rssi_iterations,
|
||||
device_64_bits_address_,
|
||||
database_addresses_inv_[packet_loss_it_->first]);
|
||||
serial_device_->Send_Frame(frame);
|
||||
sent_request++;
|
||||
|
||||
rssi_result_map_it_ = rssi_result_map_.find(target_id);
|
||||
if(rssi_result_map_it_ == rssi_result_map_.end())
|
||||
{
|
||||
RSSI_Result result ={rssi_payload_size, rssi_iterations, 0, 0, 0,
|
||||
0, 0, 0, 0, TRIGGERED};
|
||||
rssi_result_map_[database_addresses_it_->second] = result;
|
||||
}
|
||||
else
|
||||
{
|
||||
rssi_result_map_it_->second.payload_size = rssi_payload_size;
|
||||
rssi_result_map_it_->second.iterations = rssi_iterations;
|
||||
rssi_result_map_it_->second.avg_rssi = TRIGGERED;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return sent_request;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
float PacketsHandler::computePercentage(const int16_t numerator, const int16_t denumerator) const
|
||||
{
|
||||
return static_cast<float>((numerator * 100.0) / (denumerator * 1.0));
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
float PacketsHandler::filterIIR(const float new_val, const float old_val, const float gain) const
|
||||
{
|
||||
return (new_val * (1.0 - gain)) + (old_val * gain);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
void PacketsHandler::processPacketLoss(const char* packet_loss)
|
||||
{
|
||||
uint8_t source_ID = static_cast<uint8_t>(packet_loss[1]);
|
||||
uint16_t received_packet_from_me = static_cast<uint16_t>(
|
||||
static_cast<uint16_t>(static_cast<unsigned char>(packet_loss[2])) << 8 |
|
||||
static_cast<uint16_t>(static_cast<unsigned char>(packet_loss[3])));
|
||||
uint8_t packet_loss_msg_id = static_cast<uint8_t>(packet_loss[4]);
|
||||
|
||||
packet_loss_it_ = packet_loss_map_.find(source_ID);
|
||||
|
||||
if (packet_loss_it_ != packet_loss_map_.end())
|
||||
{
|
||||
if (packet_loss_msg_id == packet_loss_it_->second.packet_loss_received_id_)
|
||||
{
|
||||
packet_loss_it_->second.packet_loss_received_id_ = (packet_loss_it_->second.packet_loss_received_id_ + 1) % MAX_PACKET_LOSS_MSG_ID;
|
||||
updatePacketLoss(packet_loss_it_->second, received_packet_from_me);
|
||||
}
|
||||
else
|
||||
{
|
||||
// Missed a packet(s) loss msg, thus we resynchronize the id
|
||||
packet_loss_it_->second.packet_loss_received_id_ = (packet_loss_msg_id + 1) % MAX_PACKET_LOSS_MSG_ID;
|
||||
printf("Resynchronized %i\n", packet_loss_it_->second.packet_loss_received_id_);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
database_addresses_inv_it_ = database_addresses_inv_.find(source_ID);
|
||||
if (database_addresses_inv_it_ != database_addresses_inv_.end())
|
||||
{
|
||||
uint64_t long_address = database_addresses_inv_it_->second;
|
||||
packet_loss_map_.insert(std::pair<uint8_t, On_Line_Node_S>(source_ID,
|
||||
{long_address, 0.0, 0.0, 0, 0, 0, 0}));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
void PacketsHandler::updatePacketLoss(On_Line_Node_S& node, const uint16_t received_packet)
|
||||
/* Description: Update the packet loss of the node: node.
|
||||
* The information received is condered valid only if:
|
||||
* - The number of sent packets is different from 0
|
||||
* - The number of received packets is inferior to sent_packets + 2
|
||||
*
|
||||
* The + 2 allows the system to take into consideration the messages sent after
|
||||
* the packet loss information messages was sent.
|
||||
------------------------------------------------------------------ */
|
||||
{
|
||||
if(node.sent_packets_ != 0) // Division by 0
|
||||
{
|
||||
if(node.sent_packets_ + 2 >= received_packet)
|
||||
{
|
||||
node.packet_loss_raw_ = computePercentage((static_cast<int16_t>(node.sent_packets_) - static_cast<int16_t>(received_packet)),
|
||||
node.sent_packets_);
|
||||
node.packet_loss_filtered_ = filterIIR(node.packet_loss_raw_,
|
||||
node.packet_loss_filtered_,
|
||||
PACKET_LOSS_FILTER_GAIN);
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("Impossible received packet number: %i for %i sent (coming from %lu)",
|
||||
static_cast<int>(received_packet),
|
||||
static_cast<int>(node.sent_packets_),
|
||||
static_cast<long>(node.device_64_bits_address_));
|
||||
}
|
||||
node.sent_packets_ = 0;
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
void PacketsHandler::sendPacketLoss()
|
||||
{
|
||||
for (auto& it:packet_loss_map_)
|
||||
{
|
||||
std::string packet_loss_message = PACKET_LOSS_IDENTIFIER;
|
||||
std::string packet_loss_frame;
|
||||
|
||||
packet_loss_message.push_back(device_address_);
|
||||
packet_loss_message.push_back((it.second.received_packets_ & 0xFF00) >> 8);
|
||||
packet_loss_message.push_back(it.second.received_packets_ & 0x00FF);
|
||||
packet_loss_message.push_back(it.second.packet_loss_sent_id_);
|
||||
|
||||
it.second.received_packets_ = 0;
|
||||
it.second.packet_loss_sent_id_ = (it.second.packet_loss_sent_id_ + 1) % MAX_PACKET_LOSS_MSG_ID;
|
||||
|
||||
// MSG format L source id received packets packet loss msg id
|
||||
// 1 byte 8 bits 16 bits 8 bits
|
||||
Generate_Transmit_Request_Frame(packet_loss_message.c_str(),
|
||||
&packet_loss_frame,
|
||||
packet_loss_message.size(),
|
||||
static_cast<unsigned char>(0x01),
|
||||
int_to_hex(it.second.device_64_bits_address_, 16),
|
||||
int_to_hex(static_cast<int>(it.first), 4));
|
||||
|
||||
serial_device_->Send_Frame(packet_loss_frame);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t PacketsHandler::ucharToUint16(unsigned char msb, unsigned char lsb)
|
||||
/* Description: return the numerical value of the corresponding
|
||||
* binary number msb lsb
|
||||
------------------------------------------------------------------ */
|
||||
{
|
||||
return (static_cast<uint16_t>(msb)<<8) + static_cast<uint16_t>(lsb);
|
||||
}
|
||||
|
||||
inline uint64_t PacketsHandler::get64BitsAddress(const char* bytes,
|
||||
const int offset)
|
||||
{
|
||||
return (
|
||||
static_cast<uint64_t>(static_cast<unsigned char>(bytes[offset])) << 56 |
|
||||
static_cast<uint64_t>(static_cast<unsigned char>(bytes[offset + 1])) << 48 |
|
||||
static_cast<uint64_t>(static_cast<unsigned char>(bytes[offset + 2])) << 40 |
|
||||
static_cast<uint64_t>(static_cast<unsigned char>(bytes[offset + 3])) << 32 |
|
||||
static_cast<uint64_t>(static_cast<unsigned char>(bytes[offset + 4])) << 24 |
|
||||
static_cast<uint64_t>(static_cast<unsigned char>(bytes[offset + 5])) << 16 |
|
||||
static_cast<uint64_t>(static_cast<unsigned char>(bytes[offset + 6])) << 8 |
|
||||
static_cast<uint64_t>(static_cast<unsigned char>(bytes[offset + 7])));
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -104,14 +104,12 @@ void SerialDevice::Close_Serial_Port()
|
|||
void SerialDevice::Set_In_Messages_Pointers(Thread_Safe_Deque* in_std_messages,
|
||||
Thread_Safe_Deque* in_fragments,
|
||||
Thread_Safe_Deque* in_Acks_and_Pings,
|
||||
Thread_Safe_Deque* command_responses,
|
||||
Thread_Safe_Deque* in_packet_loss)
|
||||
Thread_Safe_Deque* command_responses)
|
||||
{
|
||||
in_std_messages_ = in_std_messages;
|
||||
in_fragments_ = in_fragments;
|
||||
in_Acks_and_Pings_ = in_Acks_and_Pings;
|
||||
command_responses_ = command_responses;
|
||||
in_packet_loss_ = in_packet_loss;
|
||||
}
|
||||
|
||||
|
||||
|
@ -196,13 +194,14 @@ void SerialDevice::Read_Frame_Body()
|
|||
{
|
||||
if (!error)
|
||||
{
|
||||
if (current_frame_.Get_Frame_Type() == FRAME_TYPE_KEYS[RECEIVE_PACKET])
|
||||
if (current_frame_.Get_Frame_Type() ==
|
||||
FRAME_TYPE_KEYS[RECEIVE_PACKET])
|
||||
{
|
||||
char msg_type = current_frame_.Get_Message_Type();
|
||||
std::shared_ptr<std::string> in_message =
|
||||
std::make_shared<std::string>();
|
||||
|
||||
if (msg_type == FRAGMENT_MSG_ID)
|
||||
if (msg_type == 'F')
|
||||
{
|
||||
in_message->append(current_frame_.Get_Frame_Body()
|
||||
+ 11,
|
||||
|
@ -210,31 +209,19 @@ void SerialDevice::Read_Frame_Body()
|
|||
in_fragments_->Push_Back(in_message);
|
||||
}
|
||||
|
||||
else if (msg_type == ACKNOWLEDGEMENT_MSG_ID || msg_type == PING_MSG_ID)
|
||||
else if (msg_type == 'A' || msg_type == 'P')
|
||||
{
|
||||
in_message->append(current_frame_.Get_Frame_Body(),
|
||||
current_frame_.Get_Frame_Body_Length() - 1);
|
||||
in_Acks_and_Pings_->Push_Back(in_message);
|
||||
}
|
||||
|
||||
else if (msg_type == STANDARD_MSG_ID)
|
||||
else if (msg_type == 'S')
|
||||
{
|
||||
in_message->append(current_frame_.Get_Frame_Body() + 12,
|
||||
current_frame_.Get_Frame_Body_Length() - 13);
|
||||
in_std_messages_->Push_Back(in_message);
|
||||
}
|
||||
|
||||
else if (msg_type == PACKET_LOSS_MSG_ID)
|
||||
{
|
||||
in_message->append(current_frame_.Get_Frame_Body() + 11,
|
||||
current_frame_.Get_Frame_Body_Length() - 12);
|
||||
in_packet_loss_->Push_Back(in_message);
|
||||
}
|
||||
|
||||
else
|
||||
{
|
||||
// nothing to do
|
||||
}
|
||||
}
|
||||
else if (current_frame_.Get_Frame_Type() ==
|
||||
FRAME_TYPE_KEYS[AT_COMMAND_RESPONSE])
|
||||
|
@ -247,18 +234,6 @@ void SerialDevice::Read_Frame_Body()
|
|||
|
||||
command_responses_->Push_Back(in_message);
|
||||
}
|
||||
else if (current_frame_.Get_Frame_Type() ==
|
||||
FRAME_TYPE_KEYS[EXPLICIT_RX_INDICATOR])
|
||||
{
|
||||
std::shared_ptr<std::string> in_message =
|
||||
std::make_shared<std::string>();
|
||||
|
||||
in_message->append(current_frame_.Get_Frame_Body() + 17,
|
||||
current_frame_.Get_Frame_Body_Length() - 18);
|
||||
in_message->insert(in_message->begin(), 'S');
|
||||
in_message->insert(in_message->begin(), 'R');
|
||||
command_responses_->Push_Back(in_message);
|
||||
}
|
||||
|
||||
Read_Frame_Header();
|
||||
}
|
||||
|
@ -305,6 +280,7 @@ void SerialDevice::Reset_IO_Service()
|
|||
io_service_.reset();
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -3,76 +3,58 @@
|
|||
/* September 20, 2016 -- @Copyright Aymen Soussia. All rights reserved. */
|
||||
/* (aymen.soussia@gmail.com) */
|
||||
|
||||
|
||||
#include <climits>
|
||||
#include <stdlib.h>
|
||||
#include <time.h>
|
||||
|
||||
#include <mavros_msgs/Mavlink.h>
|
||||
#include "mavros_msgs/ParamGet.h"
|
||||
#include <ros/ros.h>
|
||||
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
void Receive_Payload_Callback(
|
||||
const mavros_msgs::Mavlink::ConstPtr &mavlink_msg) {
|
||||
void Receive_Payload_Callback(const mavros_msgs::Mavlink::ConstPtr& mavlink_msg)
|
||||
{
|
||||
std::cout << "Received Mavlink Message:" << std::endl;
|
||||
for (unsigned short i = 0; i < mavlink_msg->payload64.size(); i++)
|
||||
std::cout << mavlink_msg->payload64.at(i) << std::endl;
|
||||
std::cout << std::endl;
|
||||
}
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
unsigned int Get_Random_Size(unsigned int min, unsigned int max) {
|
||||
unsigned int Get_Random_Size(unsigned int min, unsigned int max)
|
||||
{
|
||||
return rand() % (max - min) + min;
|
||||
}
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
unsigned long long Get_Random_Int64(unsigned long long min,
|
||||
unsigned long long max) {
|
||||
unsigned long long Get_Random_Int64(unsigned long long min, unsigned long long max)
|
||||
{
|
||||
return rand() % (max - min) + min;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
void Init_Random_Seed() { srand(time(NULL)); }
|
||||
|
||||
//*****************************************************************************
|
||||
int main(int argc, char **argv) {
|
||||
const unsigned int MIN_PAYLOAD_SIZE = 1;
|
||||
const unsigned int MAX_PAYLOAD_SIZE = 5;
|
||||
const int DEFAULT_RATE = 10;
|
||||
int rate = DEFAULT_RATE;
|
||||
void Init_Random_Seed()
|
||||
{
|
||||
srand (time(NULL));
|
||||
}
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
const unsigned int MIN_PAYLOAD_SIZE = 750;
|
||||
const unsigned int MAX_PAYLOAD_SIZE = 752;
|
||||
|
||||
ros::init(argc, argv, "test_buzz");
|
||||
|
||||
ros::NodeHandle node_handle;
|
||||
ros::Publisher mavlink_pub =
|
||||
node_handle.advertise<mavros_msgs::Mavlink>("outMavlink", 1000);
|
||||
ros::Subscriber mavlink_sub =
|
||||
node_handle.subscribe("inMavlink", 1000, Receive_Payload_Callback);
|
||||
|
||||
mavros_msgs::Mavlink mavlink_msg_;
|
||||
mavlink_msg_.msgid = 1;
|
||||
if (argc > 1) {
|
||||
try
|
||||
{
|
||||
rate = atoi(argv[1]);
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
rate = DEFAULT_RATE;
|
||||
}
|
||||
}
|
||||
|
||||
ros::ServiceClient xbeestatus_srv;
|
||||
xbeestatus_srv = node_handle.serviceClient<mavros_msgs::ParamGet>("/network_status");
|
||||
mavros_msgs::ParamGet::Request robot_id_srv_request; robot_id_srv_request.param_id="id";
|
||||
mavros_msgs::ParamGet::Response robot_id_srv_response;
|
||||
while(!xbeestatus_srv.call(robot_id_srv_request,robot_id_srv_response)){
|
||||
ros::Duration(0.1).sleep();
|
||||
ROS_WARN("Waiting for Xbee to respond to get device ID");
|
||||
}
|
||||
mavlink_msg_.sysid=robot_id_srv_response.value.integer;
|
||||
|
||||
ros::Rate loop_rate(rate);
|
||||
ros::Publisher mavlink_pub = node_handle.advertise<mavros_msgs::Mavlink>("outMavlink", 1000);
|
||||
ros::Subscriber mavlink_sub = node_handle.subscribe("inMavlink", 1000, Receive_Payload_Callback);
|
||||
|
||||
Init_Random_Seed();
|
||||
|
||||
|
@ -84,18 +66,21 @@ int main(int argc, char **argv) {
|
|||
|
||||
while (ros::ok() && std::cin.getline(line, MAX_BUFFER_SIZE))
|
||||
{
|
||||
mavros_msgs::Mavlink mavlink_msg_;
|
||||
mavlink_msg_.sysid = 2;
|
||||
mavlink_msg_.msgid = 1;
|
||||
|
||||
unsigned int payload_size =
|
||||
Get_Random_Size(MIN_PAYLOAD_SIZE, MAX_PAYLOAD_SIZE);
|
||||
mavlink_msg_.payload64.clear();
|
||||
unsigned int payload_size = Get_Random_Size(MIN_PAYLOAD_SIZE, MAX_PAYLOAD_SIZE);
|
||||
|
||||
for (unsigned int i = 0; i < payload_size; i++) {
|
||||
for (unsigned int i = 0; i < payload_size; i++)
|
||||
{
|
||||
mavlink_msg_.payload64.push_back(Get_Random_Int64(1, ULLONG_MAX));
|
||||
}
|
||||
|
||||
std::cout << "Sent Mavlink Message " << count << std::endl;
|
||||
|
||||
for (unsigned int i = 0; i < payload_size; i++) {
|
||||
for (unsigned int i = 0; i < payload_size; i++)
|
||||
{
|
||||
std::cout << mavlink_msg_.payload64.at(i) << std::endl;
|
||||
}
|
||||
|
||||
|
@ -104,7 +89,6 @@ int main(int argc, char **argv) {
|
|||
mavlink_pub.publish(mavlink_msg_);
|
||||
|
||||
ros::spinOnce();
|
||||
loop_rate.sleep();
|
||||
|
||||
count++;
|
||||
std::cout << "Press Enter to Send New Mavlink Message..." << std::endl;
|
||||
|
|
|
@ -1,114 +0,0 @@
|
|||
/* RosBuzz.cpp -- Basic ROS Buzz node -- */
|
||||
/* ------------------------------------------------------------------------- */
|
||||
/* September 20, 2016 -- @Copyright Aymen Soussia. All rights reserved. */
|
||||
/* (aymen.soussia@gmail.com) */
|
||||
|
||||
#include <climits>
|
||||
#include <stdlib.h>
|
||||
#include <time.h>
|
||||
|
||||
#include <mavros_msgs/Mavlink.h>
|
||||
#include "mavros_msgs/ParamGet.h"
|
||||
#include <ros/ros.h>
|
||||
|
||||
//*****************************************************************************
|
||||
void Receive_Payload_Callback(
|
||||
const mavros_msgs::Mavlink::ConstPtr &mavlink_msg) {
|
||||
std::cout << "Received Mavlink Message:" << std::endl;
|
||||
for (unsigned short i = 0; i < mavlink_msg->payload64.size(); i++)
|
||||
std::cout << mavlink_msg->payload64.at(i) << std::endl;
|
||||
std::cout << std::endl;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
unsigned int Get_Random_Size(unsigned int min, unsigned int max) {
|
||||
return rand() % (max - min) + min;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
unsigned long long Get_Random_Int64(unsigned long long min,
|
||||
unsigned long long max) {
|
||||
return rand() % (max - min) + min;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
void Init_Random_Seed() { srand(time(NULL)); }
|
||||
|
||||
//*****************************************************************************
|
||||
int main(int argc, char **argv) {
|
||||
const unsigned int MIN_PAYLOAD_SIZE = 10;
|
||||
const unsigned int MAX_PAYLOAD_SIZE = 32;
|
||||
const int DEFAULT_RATE = 10;
|
||||
int rate = DEFAULT_RATE;
|
||||
|
||||
ros::init(argc, argv, "test_buzz");
|
||||
|
||||
ros::NodeHandle node_handle;
|
||||
ros::Publisher mavlink_pub =
|
||||
node_handle.advertise<mavros_msgs::Mavlink>("outMavlink", 1000);
|
||||
ros::Subscriber mavlink_sub =
|
||||
node_handle.subscribe("inMavlink", 1000, Receive_Payload_Callback);
|
||||
|
||||
mavros_msgs::Mavlink mavlink_msg_;
|
||||
mavlink_msg_.msgid = 1;
|
||||
if (argc > 1) {
|
||||
try
|
||||
{
|
||||
rate = atoi(argv[1]);
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
rate = DEFAULT_RATE;
|
||||
}
|
||||
}
|
||||
|
||||
ros::ServiceClient xbeestatus_srv;
|
||||
xbeestatus_srv = node_handle.serviceClient<mavros_msgs::ParamGet>("network_status");
|
||||
mavros_msgs::ParamGet::Request robot_id_srv_request; robot_id_srv_request.param_id="id";
|
||||
mavros_msgs::ParamGet::Response robot_id_srv_response;
|
||||
while(!xbeestatus_srv.call(robot_id_srv_request,robot_id_srv_response)){
|
||||
ros::Duration(0.1).sleep();
|
||||
ROS_WARN("Waiting for Xbee to respond to get device ID");
|
||||
}
|
||||
mavlink_msg_.sysid=robot_id_srv_response.value.integer;
|
||||
|
||||
ros::Rate loop_rate(rate);
|
||||
|
||||
Init_Random_Seed();
|
||||
|
||||
int count = 0;
|
||||
// const std::size_t MAX_BUFFER_SIZE = 64;
|
||||
// char line[MAX_BUFFER_SIZE];
|
||||
|
||||
std::cout << "Press Enter to Send New Mavlink Message..." << std::endl;
|
||||
|
||||
while (ros::ok()) //&& std::cin.getline(line, MAX_BUFFER_SIZE))
|
||||
{
|
||||
|
||||
unsigned int payload_size =
|
||||
Get_Random_Size(MIN_PAYLOAD_SIZE, MAX_PAYLOAD_SIZE);
|
||||
mavlink_msg_.payload64.clear();
|
||||
|
||||
for (unsigned int i = 0; i < payload_size; i++) {
|
||||
mavlink_msg_.payload64.push_back(Get_Random_Int64(1, ULLONG_MAX));
|
||||
}
|
||||
|
||||
std::cout << "Sent Mavlink Message " << count << std::endl;
|
||||
|
||||
/*for (unsigned int i = 0; i < payload_size; i++) {
|
||||
std::cout << mavlink_msg_.payload64.at(i) << std::endl;
|
||||
}*/
|
||||
|
||||
std::cout << std::endl;
|
||||
|
||||
mavlink_pub.publish(mavlink_msg_);
|
||||
|
||||
ros::spinOnce();
|
||||
loop_rate.sleep();
|
||||
|
||||
count++;
|
||||
// std::cout << "Press Enter to Send New Mavlink Message..." << std::endl;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
|
@ -1,70 +0,0 @@
|
|||
/* ----------------------------------------------------------------
|
||||
* File: XBeeSetup.cpp
|
||||
* Date: 02/06/2017
|
||||
* Author: Pierre-Yves Breches
|
||||
* Description: Implementation of the xbeeSetup function to
|
||||
* configure the xbee module
|
||||
* Copyright Humanitas Solutions. All rights reserved.
|
||||
------------------------------------------------------------------ */
|
||||
|
||||
#include "XBeeSetup.h"
|
||||
|
||||
bool setupXBee(const std::string &device_port, const unsigned int baud_rate) {
|
||||
XBeeModule xbee_module;
|
||||
XMLConfigParser config_parser;
|
||||
|
||||
if (xbee_module.Init_Port(device_port, baud_rate)) {
|
||||
std::thread th_service(&XBeeModule::Run_Service, &xbee_module);
|
||||
|
||||
while (!xbee_module.Is_Connected() &&
|
||||
!xbee_module.Check_Time_Out_Exceeded()) {
|
||||
continue;
|
||||
}
|
||||
|
||||
if (xbee_module.Is_Connected()) {
|
||||
std::cout << "Connected to XBee." << std::endl;
|
||||
std::cout << "Loading Config File..." << std::endl;
|
||||
|
||||
if (config_parser.Load_Config()) {
|
||||
std::cout << "Config Loaded Successfully." << std::endl;
|
||||
std::cout << "Transferring Data..." << std::endl;
|
||||
std::vector<XBee_Parameter_S> *config_parameters =
|
||||
config_parser.Get_Loaded_Parameters();
|
||||
|
||||
for (std::size_t i = 0; i < config_parameters->size(); i++) {
|
||||
std::string current_command;
|
||||
xbee_module.Format_AT_Command(config_parameters->at(i),
|
||||
¤t_command);
|
||||
xbee_module.Send_Data(current_command);
|
||||
}
|
||||
|
||||
std::string write_command = "ATWR \r";
|
||||
xbee_module.Send_Data(write_command);
|
||||
}
|
||||
}
|
||||
|
||||
th_service.join();
|
||||
|
||||
std::cout << "Exiting AT Command Mode..." << std::endl;
|
||||
|
||||
if (xbee_module.Is_Connected())
|
||||
{
|
||||
xbee_module.Exit_AT_Command_Mode();
|
||||
|
||||
if (config_parser.Is_Config_Loaded_Successfully())
|
||||
{
|
||||
std::cout << "XBee Configured Successfully." << std::endl;
|
||||
return true;
|
||||
}
|
||||
else
|
||||
{
|
||||
std::cout << "XBee Configuration Failed." << std::endl;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
std::cout << "XBee Configuration Failed." << std::endl;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
37
src/Xbee.cpp
37
src/Xbee.cpp
|
@ -3,15 +3,18 @@
|
|||
/* September 20, 2016 -- @Copyright Aymen Soussia. All rights reserved. */
|
||||
/* (aymen.soussia@gmail.com) */
|
||||
|
||||
#include "XBeeSetup.h"
|
||||
|
||||
#include "CommunicationManager.h"
|
||||
#include <climits>
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
int main(int argc, char *argv[]) {
|
||||
int main(int argc, char* argv[])
|
||||
{
|
||||
|
||||
try {
|
||||
try
|
||||
{
|
||||
ros::init(argc, argv, "xbee");
|
||||
ros::NodeHandle node_handle;
|
||||
|
||||
Mist::Xbee::CommunicationManager communication_manager;
|
||||
std::string device;
|
||||
|
@ -21,18 +24,17 @@ int main(int argc, char *argv[]) {
|
|||
Mist::Xbee::CommunicationManager::RUNNING_MODE running_mode =
|
||||
Mist::Xbee::CommunicationManager::RUNNING_MODE::SOLO;
|
||||
|
||||
if (argc > 1) {
|
||||
if (argc > 1)
|
||||
{
|
||||
if (!strcmp(argv[1], "master"))
|
||||
drone_type = Mist::Xbee::CommunicationManager::DRONE_TYPE::MASTER;
|
||||
|
||||
if (argc > 2) {
|
||||
if (argc > 2)
|
||||
{
|
||||
if (!strcmp(argv[2], "swarm"))
|
||||
running_mode = Mist::Xbee::CommunicationManager::RUNNING_MODE::SWARM;
|
||||
}
|
||||
}
|
||||
|
||||
ros::NodeHandle node_handle;
|
||||
|
||||
if (!node_handle.getParam("USB_port", device))
|
||||
{
|
||||
std::cout << "Failed to Get Topic Name: param 'USB_port' Not Found." << std::endl;
|
||||
|
@ -44,26 +46,13 @@ int main(int argc, char *argv[]) {
|
|||
std::cout << "Failed to Get Topic Name: param 'Baud_rate' Not Found." << std::endl;
|
||||
return EXIT_FAILURE;
|
||||
}
|
||||
|
||||
//setupXBee(device, static_cast<std::size_t>(baud_rate));
|
||||
|
||||
std::cout << "Going to init !!!!" << std::endl;
|
||||
|
||||
if (communication_manager.Init(device, static_cast<std::size_t>(baud_rate)))
|
||||
{
|
||||
communication_manager.Run(drone_type, running_mode);
|
||||
}
|
||||
}
|
||||
catch (const std::exception& e)
|
||||
{
|
||||
std::cout << "Error: " << e.what() << std::endl;
|
||||
std::cout << "Please Try One of The Following Options:" << std::endl;
|
||||
std::cout << " 1) Change The Baud Rate. Make Sure It Matches The Current Baud Rate Used by The XBee (By default BD = 9600 bps)." << std::endl;
|
||||
std::cout << " 2) Change The Specified Device (e.g. COM1 for Windows or /dev/tty/USB0 for Linux)." << std::endl;
|
||||
std::cout << " 3) Disconnect and Connect The XBee." << std::endl;
|
||||
std::cout << " 4) Press The Reset Button on The XBee." << std::endl;
|
||||
std::cout << " 5) Update The Firmware With XCTU." << std::endl;
|
||||
std::cout << "XBee Configuration Failed." << std::endl;
|
||||
std::cout << "Error Occured:" << std::endl;
|
||||
std::cout << e.what() << std::endl;
|
||||
}
|
||||
catch (...)
|
||||
{
|
||||
|
|
|
@ -1,169 +0,0 @@
|
|||
/* ----------------------------------------------------------------
|
||||
* File: frame_generators.cpp
|
||||
* Created on: 21/06/2017
|
||||
* Author: Pierre-Yves Breches
|
||||
* Description: This file contains functions used for the the creation of xbee
|
||||
* frame
|
||||
* Copyright Humanitas Solutions. All rights reserved.
|
||||
------------------------------------------------------------------ */
|
||||
|
||||
#include "frame_generators.h"
|
||||
|
||||
namespace Mist
|
||||
{
|
||||
|
||||
namespace Xbee
|
||||
{
|
||||
void Generate_Transmit_Request_Frame(
|
||||
const char* message,
|
||||
std::string * frame,
|
||||
const std::size_t message_size,
|
||||
const unsigned char frame_ID,
|
||||
const std::string& destination_adssress,
|
||||
const std::string& short_destination_adress,
|
||||
const std::string& broadcast_radius,
|
||||
const std::string& options)
|
||||
/* Description: Generate a link testing frame as presented page 73-74
|
||||
* in Ressources/XbeeModule_Datasheet.pdf
|
||||
------------------------------------------------------------------ */
|
||||
{
|
||||
const unsigned char FRAME_TYPE = static_cast<unsigned char>(0x10); /* Transmit Request Frame */
|
||||
std::string frame_parameters;
|
||||
std::string bytes_frame_parameters;
|
||||
|
||||
frame_parameters.append(destination_adssress);
|
||||
frame_parameters.append(short_destination_adress);
|
||||
frame_parameters.append(broadcast_radius);
|
||||
frame_parameters.append(options);
|
||||
|
||||
Convert_HEX_To_Bytes(frame_parameters, &bytes_frame_parameters);
|
||||
|
||||
frame->push_back(FRAME_TYPE);
|
||||
frame->push_back(frame_ID);
|
||||
frame->append(bytes_frame_parameters);
|
||||
frame->append(message, message_size);
|
||||
|
||||
Calculate_and_Append_Checksum(frame);
|
||||
Add_Length_and_Start_Delimiter(frame);
|
||||
}
|
||||
|
||||
void generateLinkTestingFrame(std::string* frame,
|
||||
uint16_t rssi_payload_size,
|
||||
uint16_t rssi_iterations,
|
||||
std::string device_64_bits_address,
|
||||
uint64_t target_64_bits_address)
|
||||
/* Description: Generate a link testing frame as presented page 29-30
|
||||
* in Ressources/XbeeModule_Datasheet.pdf
|
||||
------------------------------------------------------------------ */
|
||||
{
|
||||
static const unsigned char FRAME_TYPE = static_cast<unsigned char>(0x11);
|
||||
static const unsigned char FRAME_ID = static_cast<unsigned char>(0x01);
|
||||
static const std::string link_testing_params = "FFFEE6E60014C1050000";
|
||||
|
||||
std::string frame_parameters;
|
||||
std::string bytes_frame_parameters;
|
||||
|
||||
frame_parameters = link_testing_params;
|
||||
frame_parameters += int_to_hex(target_64_bits_address, 16);
|
||||
frame_parameters += int_to_hex(rssi_payload_size, 4); // packet size for testing
|
||||
frame_parameters += int_to_hex(rssi_iterations, 4); // number of iterations
|
||||
|
||||
Convert_HEX_To_Bytes(frame_parameters, &bytes_frame_parameters);
|
||||
|
||||
frame->push_back(FRAME_TYPE);
|
||||
frame->push_back(FRAME_ID);
|
||||
frame->append(device_64_bits_address);
|
||||
frame->append(bytes_frame_parameters);
|
||||
|
||||
Calculate_and_Append_Checksum(frame);
|
||||
Add_Length_and_Start_Delimiter(frame);
|
||||
}
|
||||
|
||||
|
||||
void Generate_AT_Command(const char* command,
|
||||
std::string* frame,
|
||||
const unsigned char frame_ID)
|
||||
/* Description: Generate an AT command frame as decribed page 73
|
||||
* in Ressources/XbeeModule_Datasheet.pdf
|
||||
------------------------------------------------------------------ */
|
||||
{
|
||||
const unsigned char FRAME_TYPE = static_cast<unsigned char>(0x09);/* AT Command Frame */
|
||||
std::string temporary_parameter_value;
|
||||
|
||||
frame->push_back(FRAME_TYPE);
|
||||
frame->push_back(frame_ID);
|
||||
frame->append(command);
|
||||
|
||||
Calculate_and_Append_Checksum(frame);
|
||||
Add_Length_and_Start_Delimiter(frame);
|
||||
}
|
||||
|
||||
void Convert_HEX_To_Bytes(const std::string& HEX_data,
|
||||
std::string* converted_data)
|
||||
/* Description:
|
||||
*
|
||||
------------------------------------------------------------------ */
|
||||
{
|
||||
const unsigned short TWO_BYTES = 2;
|
||||
char temporary_buffer[TWO_BYTES];
|
||||
unsigned char temporary_char;
|
||||
int temporary_HEX;
|
||||
|
||||
for (unsigned short i = 0; i <= HEX_data.size() - TWO_BYTES;
|
||||
i += TWO_BYTES)
|
||||
{
|
||||
memcpy(temporary_buffer, HEX_data.c_str() + i, TWO_BYTES);
|
||||
sscanf(temporary_buffer, "%02X", &temporary_HEX);
|
||||
temporary_char = static_cast<unsigned char>(temporary_HEX);
|
||||
converted_data->push_back(temporary_char);
|
||||
}
|
||||
}
|
||||
|
||||
void Calculate_and_Append_Checksum(std::string* frame)
|
||||
/* Description:
|
||||
*
|
||||
------------------------------------------------------------------ */
|
||||
{
|
||||
unsigned short bytes_sum = 0;
|
||||
unsigned lowest_8_bits = 0;
|
||||
unsigned short checksum = 0;
|
||||
unsigned char checksum_byte;
|
||||
|
||||
for (unsigned short i = 0; i < frame->size(); i++)
|
||||
bytes_sum += static_cast<unsigned short>(frame->at(i));
|
||||
|
||||
lowest_8_bits = bytes_sum & 0xFF;
|
||||
checksum = 0xFF - lowest_8_bits;
|
||||
checksum_byte = static_cast<unsigned char>(checksum);
|
||||
frame->push_back(checksum_byte);
|
||||
}
|
||||
|
||||
|
||||
void Add_Length_and_Start_Delimiter(std::string* frame)
|
||||
/* Description:
|
||||
*
|
||||
------------------------------------------------------------------ */
|
||||
{
|
||||
const unsigned short FIVE_BYTES = 5;
|
||||
const unsigned char START_DLIMITER = static_cast<unsigned char>(0x7E);
|
||||
char temporary_buffer[FIVE_BYTES];
|
||||
unsigned char temporary_char;
|
||||
int Hex_frame_length_1;
|
||||
int Hex_frame_length_2;
|
||||
std::string header;
|
||||
int frame_length = frame->size() - 1; /* frame_length = frame_size - checksum byte */
|
||||
|
||||
header.push_back(START_DLIMITER);
|
||||
sprintf(temporary_buffer, "%04X", frame_length);
|
||||
sscanf(temporary_buffer, "%02X%02X", &Hex_frame_length_1,
|
||||
&Hex_frame_length_2);
|
||||
temporary_char = static_cast<unsigned char>(Hex_frame_length_1);
|
||||
header.push_back(temporary_char);
|
||||
temporary_char = static_cast<unsigned char>(Hex_frame_length_2);
|
||||
header.push_back(temporary_char);
|
||||
frame->insert(0, header);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
}
|
67
src/main.cpp
67
src/main.cpp
|
@ -3,7 +3,70 @@
|
|||
/* November 30, 2016 -- @Copyright Aymen Soussia. All rights reserved. */
|
||||
/* (aymen.soussia@gmail.com) */
|
||||
|
||||
#include "XBeeSetup.h"
|
||||
|
||||
#include<thread>
|
||||
|
||||
#include"XBeeModule.h"
|
||||
#include"XMLConfigParser.h"
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
void Setup_XBee(const std::string& device_port, const unsigned int baud_rate)
|
||||
{
|
||||
XBeeModule xbee_module;
|
||||
XMLConfigParser config_parser;
|
||||
|
||||
if (xbee_module.Init_Port(device_port, baud_rate))
|
||||
{
|
||||
std::thread th_service(&XBeeModule::Run_Service, &xbee_module);
|
||||
|
||||
while (!xbee_module.Is_Connected() && !xbee_module.Check_Time_Out_Exceeded())
|
||||
{
|
||||
continue;
|
||||
}
|
||||
|
||||
if (xbee_module.Is_Connected())
|
||||
{
|
||||
std::cout << "Connected to XBee." << std::endl;
|
||||
std::cout << "Loading Config File..." << std::endl;
|
||||
|
||||
if (config_parser.Load_Config())
|
||||
{
|
||||
std::cout << "Config Loaded Successfully." << std::endl;
|
||||
std::cout << "Transferring Data..." << std::endl;
|
||||
std::vector<XBee_Parameter_S>* config_parameters = config_parser.Get_Loaded_Parameters();
|
||||
|
||||
for (std::size_t i = 0; i < config_parameters->size(); i++)
|
||||
{
|
||||
std::string current_command;
|
||||
xbee_module.Format_AT_Command(config_parameters->at(i), ¤t_command);
|
||||
xbee_module.Send_Data(current_command);
|
||||
}
|
||||
|
||||
std::string write_command = "ATWR \r";
|
||||
xbee_module.Send_Data(write_command);
|
||||
}
|
||||
}
|
||||
|
||||
th_service.join();
|
||||
|
||||
std::cout << "Exiting AT Command Mode..." << std::endl;
|
||||
|
||||
if (xbee_module.Is_Connected())
|
||||
{
|
||||
xbee_module.Exit_AT_Command_Mode();
|
||||
|
||||
if (config_parser.Is_Config_Loaded_Successfully())
|
||||
std::cout << "XBee Configured Successfully." << std::endl;
|
||||
else
|
||||
std::cout << "XBee Configuration Failed." << std::endl;
|
||||
}
|
||||
else
|
||||
{
|
||||
std::cout << "XBee Configuration Failed." << std::endl;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
|
@ -26,7 +89,7 @@ int main(int argc, char*argv[])
|
|||
else
|
||||
sscanf(argv[2], "%u", &baud_rate);
|
||||
|
||||
//setupXBee(device_port, baud_rate);
|
||||
Setup_XBee(device_port, baud_rate);
|
||||
}
|
||||
catch (const std::exception& e)
|
||||
{
|
||||
|
|
Reference in New Issue