From 6cb4e6b31da44c0e7531c7f0d60e2880ced11392 Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Wed, 8 Sep 2021 13:25:05 +0100 Subject: [PATCH] SITL: update simpleRover C++ JSON interface example - Provide a cmake file for cross platform builds - Modify the example to respond to throttle commands on RC channel 3 (default for Rover) - Add more detail to readme Signed-off-by: Rhys Mainwaring --- .../SITL/examples/JSON/C++/CMakeLists.txt | 13 ++++++ libraries/SITL/examples/JSON/C++/readme.md | 40 ++++++++++++++++++- .../SITL/examples/JSON/C++/simpleRover.cpp | 2 +- 3 files changed, 53 insertions(+), 2 deletions(-) create mode 100644 libraries/SITL/examples/JSON/C++/CMakeLists.txt diff --git a/libraries/SITL/examples/JSON/C++/CMakeLists.txt b/libraries/SITL/examples/JSON/C++/CMakeLists.txt new file mode 100644 index 0000000000..3e014e3e5e --- /dev/null +++ b/libraries/SITL/examples/JSON/C++/CMakeLists.txt @@ -0,0 +1,13 @@ +cmake_minimum_required(VERSION 3.5) + +project(minimal) + +set(CMAKE_CXX_STANDARD 11) + +add_executable(minimal + minimal.cpp +) + +add_executable(simpleRover + simpleRover.cpp +) diff --git a/libraries/SITL/examples/JSON/C++/readme.md b/libraries/SITL/examples/JSON/C++/readme.md index 6cf08052b2..e54ce0ca9e 100644 --- a/libraries/SITL/examples/JSON/C++/readme.md +++ b/libraries/SITL/examples/JSON/C++/readme.md @@ -4,4 +4,42 @@ This library links a simulator written in C++ with ArduPilot through a UDP JSON Connection to SITL is made via a UDP link. The physics backend should listen for incoming messages on port 9002. The sim should then reply to the IP and port the messages were received from. This is handled by libAP_JSON. This removes the need to configure the target IP and port for SITL in the physics backend. ArduPilot SITL will send an output message every 10 seconds allowing the physics backend to auto-detect. -After a connection has been made, the optional values should be set. Then the vehicle state can be sent with `SendState`. This call includes all of the required values. The `servo_out` array supports 16 servo outputs from ArduPilot. \ No newline at end of file +After a connection has been made, the optional values should be set. Then the vehicle state can be sent with `SendState`. This call includes all of the required values. The `servo_out` array supports 16 servo outputs from ArduPilot. + +### Running the `simpleRover` example + +The examples can be built using `cmake`: + +```bash +$ mkdir build && cd build +$ cmake .. +$ make +``` + +Run the `simpleRover` physics engine: + +```bash +$ ./simpleRover +``` + +Run SITL with the JSON backend: + +```bash +sim_vehicle.py -v Rover -f JSON --console --map +``` + +The rover responds to throttle commands on RC channel 3: + +```bash +# arm throttle +MANUAL> arm throttle + +# move forwards at max throttle (expected velocity 1 m/s) +MANUAL> rc 3 1900 + +# move backwards at max throttle (expected velocity -1 m/s) +MANUAL> rc 3 1100 + +# stop +MANUAL> rc 3 1500 +``` diff --git a/libraries/SITL/examples/JSON/C++/simpleRover.cpp b/libraries/SITL/examples/JSON/C++/simpleRover.cpp index 2bf879e672..51f5ac909e 100644 --- a/libraries/SITL/examples/JSON/C++/simpleRover.cpp +++ b/libraries/SITL/examples/JSON/C++/simpleRover.cpp @@ -59,7 +59,7 @@ bool simpleRover::update(simpleRover &rover, uint16_t servo_out[]) { // how fast is the rover moving double max_velocity = 1; // m/s - double body_v = _interp1D(servo_out[0], 1100, 1900, 0, max_velocity); + double body_v = _interp1D(servo_out[2], 1100, 1900, -max_velocity, max_velocity); // how fast is the rover turning // Just doing 1-D right now. This Needs a bit of system dynamics math and geometry to get to 2-D.