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 <rhys.mainwaring@me.com>
This commit is contained in:
Rhys Mainwaring 2021-09-08 13:25:05 +01:00 committed by Andrew Tridgell
parent ec5d5b4471
commit 6cb4e6b31d
3 changed files with 53 additions and 2 deletions

View File

@ -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
)

View File

@ -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. 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. 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
```

View File

@ -59,7 +59,7 @@ bool simpleRover::update(simpleRover &rover, uint16_t servo_out[]) {
// how fast is the rover moving // how fast is the rover moving
double max_velocity = 1; // m/s 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 // 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. // Just doing 1-D right now. This Needs a bit of system dynamics math and geometry to get to 2-D.