diff --git a/README.md b/README.md index e36966b8..39ed466c 100644 --- a/README.md +++ b/README.md @@ -4,6 +4,7 @@ By Sem van der Hoeven ## Table of contents - [Introduction](#introduction) +- [EMERGENCY FORCE STOP](#emergency-force-stop) - [Pin layout](#pin-layout) - [Connecting to API](#connecting-to-api) - [Installing API](#installing-api) @@ -40,6 +41,16 @@ To add new API functionality, you can do the same, but for the code in the api f # (On the edge computer) restart API sudo systemctl restart webserver ``` +## EMERGENCY FORCE STOP +If, for whatever reason, the drone does not respond to the API, you can force stop all nodes on the drone and force it to land through the pixhawk using the following commands: +```bash +# on your computer, ssh into the drone +ssh ubuntu@10.100.0.40 +# cd into the ROS2 workspace +cd ros2_ws +# stop all ROS2 nodes +drone_scripts/stop_services.sh +``` ## Pin layout A pinout of the raspberry pi can be found [here](https://www.raspberrypi.com/documentation/computers/raspberry-pi.html). The connections are visible in the table below: |Raspberry Pi pin|Function|Connected to| @@ -124,6 +135,7 @@ To enable communication with the flight computer, the following parameters shoul The optical flow sensor is a [Hex HereFlow PMW3901](https://docs.px4.io/main/en/sensor/pmw3901.html#hex-hereflow-pmw3901-optical-flow-sensor) and it's connected to the CAN port of the pixhawk. The parameters to enable the optical flow sensor are: |Parameter|Value|Function| |---|---|---| +|EKF2_OF_CTRL |1 (Enabled)|Enable optical flow sensor fusion| |UAVCAN_ENABLE|2 (Sensors automatic config)|Enable UAVCAN for sensors| |UAVCAN_SUB_FLOW|Enabled|subscribe to optical flow messages| |UAVCAN_SUB_GPS|Disabled|subscribe to GPS messages| @@ -132,8 +144,9 @@ To reverse this, and be able to use GPS, the parameters should be: |Parameter|Value|Function| |---|---|---| -|UAVCAN_ENABLE|0 (Disabled)|Enable UAVCAN for sensors| -|UAVCAN_SUB_FLOW|Disabled|subscribe to optical flow messages| +|EKF2_OF_CTRL |0 (Disabled)|Disable optical flow sensor fusion| +|UAVCAN_ENABLE|0 (Disabled)|Disable UAVCAN for sensors| +|UAVCAN_SUB_FLOW|Disabled|don't subscribe to optical flow messages| |UAVCAN_SUB_GPS|Enabled|subscribe to GPS messages| diff --git a/doc/5G RCID Presentatie.pdf b/doc/5G RCID Presentatie.pdf new file mode 100644 index 00000000..c059ef8b Binary files /dev/null and b/doc/5G RCID Presentatie.pdf differ diff --git a/doc/Afstudeerverslag_Sem_van_der_Hoeven_2162609_final.docx b/doc/Afstudeerverslag_Sem_van_der_Hoeven_2162609_final.docx deleted file mode 100644 index dd50d1e2..00000000 Binary files a/doc/Afstudeerverslag_Sem_van_der_Hoeven_2162609_final.docx and /dev/null differ diff --git a/doc/Afstudeerverslag_Sem_van_der_Hoeven_2162609_final.pdf b/doc/Afstudeerverslag_Sem_van_der_Hoeven_2162609_final.pdf new file mode 100644 index 00000000..4f651550 Binary files /dev/null and b/doc/Afstudeerverslag_Sem_van_der_Hoeven_2162609_final.pdf differ diff --git a/src/api_communication/api_communication/api_listener.py b/src/api_communication/api_communication/api_listener.py index 57e1f5cc..c51d4d2f 100644 --- a/src/api_communication/api_communication/api_listener.py +++ b/src/api_communication/api_communication/api_listener.py @@ -294,7 +294,7 @@ class ApiListener(Node): self.move_position_request.front_back = 0.0 self.move_position_request.angle = 0.0 self.send_move_position_request() - future = self.land_drone_client.call_async(self.land_drone_request) + future = self.land_client.call_async(self.land_request) future.add_done_callback(partial(self.land_service_callback)) def arm_disarm(self):