SITL: JSON examples: update readme
This commit is contained in:
parent
5d9e0cb58d
commit
66cbed78f5
@ -1,3 +1,5 @@
|
||||
This is a example MATLAB multicopter backend for the JSON SITL interface. Its mostly physics based, Copter.m is used to setup the property's of the vehicle. This does some basic performance plots of motor thrust and power from the given motor and propeller parameters. The vehicle parameters are then saved in a .mat file, Hexsoon.mat in this case as the model is roughly based on the Hexsoon EDU450. This file is then loaded into SIM_multicopter.m and the connection to SITL started. SIM_multicopter is written in such a way that it should be simple to save a set of parameters for another vehicle type, such as a hexacopter and run them with the same model.
|
||||
|
||||
There are many simplifications in the model, the most egregious of which is a arbitrary thrust multiplier to get a sensible hover thrust from the correct vehicle parameters.
|
||||
There are many simplifications in the model, the most egregious of which is a arbitrary thrust multiplier to get a sensible hover thrust from the correct vehicle parameters.
|
||||
|
||||
A update dynamics function is included, this takes the forces and moments acting on the vehicle and calculates the states required by ArduPilot. It should be possible to reuse this function with any vehicle removing the need to duplicate the time integration scheme.
|
@ -6,15 +6,14 @@ see Copter/SIM_multicopter.m for example usage.
|
||||
|
||||
The function is defined as:
|
||||
```
|
||||
SITL_connector(target_ip,state,init_function,physics_function,delta_t)
|
||||
SITL_connector(state,init_function,physics_function,max_timestep)
|
||||
```
|
||||
- target_ip: the IP address of the machine running SITL eg '127.0.0.1'
|
||||
|
||||
- state: this is the persistent physics state of the vehicle its is a structure and must contain the following felids:
|
||||
```
|
||||
state.gyro(roll, pitch, yaw) (radians/sec) body frame
|
||||
state.attitude(roll, pitch yaw) (radians)
|
||||
state.accel(north, east, down) (m/s^2) body frame
|
||||
state.accel(x, y, z) (m/s^2) body frame
|
||||
state.velocity(north, east,down) (m/s) earth frame
|
||||
state.position(north, east, down) (m) earth frame
|
||||
```
|
||||
@ -22,14 +21,14 @@ the structure can have also any other felids required for the physics model
|
||||
|
||||
- init_function: function handle that will be called to init the physics model, this will be called on the first run and after a SITL reboot. It should take and return the state.
|
||||
function state init(state)
|
||||
init_function = @(state)init(state);
|
||||
init_function = @init;
|
||||
|
||||
- physics_function: function handle that will be called to update the physics model by a single time step. It should take in the state and array of 16 PWM inputs and return the state.
|
||||
```
|
||||
function state = physics_step(pwm_in,state)
|
||||
physics_function = @(pwm_in,state)physics_step(pwm_in,state);
|
||||
physics_function = @physics_step;
|
||||
```
|
||||
- delta_t: time step size the physics model wil use in seconds. Note that this is directly connected to the maximum speed you can run SITL at.
|
||||
- max_timestep: this is the maximum allowed time step size, the desired time step can be set with the SIM_RATE_HZ ArduPilot parameter.
|
||||
|
||||
The JSON SITL interface is lock-step scheduled. This allows matlab breakpoints to work as normal.
|
||||
|
||||
|
@ -2,31 +2,39 @@ The JSON SITL backend allows software to easily interface with ArduPilot using a
|
||||
|
||||
To launch the JSON backend run SITL with ```-f json:127.0.0.1``` where 127.0.0.1 is replaced with the IP the physics backend is running at.
|
||||
|
||||
Connection to SITL is made via a UDP link, port 9002 should be used to receive inputs from ArduPilot and port 9003 to return attitude information to ArduPilot.
|
||||
Connection to SITL is made via a UDP link on port 9002.
|
||||
|
||||
SITL output
|
||||
Data is output from SITL in a binary format:
|
||||
```
|
||||
uint32_t frame_count
|
||||
float Speedup
|
||||
uint16_t pwm[16]
|
||||
uint16 magic = 18458
|
||||
uint16 frame_rate
|
||||
uint32 frame_count
|
||||
uint16 pwm[16]
|
||||
```
|
||||
The frame_count will increment for each output frame sent by ArduPilot, this count can be used to detect lost or duplicate frames. This count will be reset when SITL is re-started allowing the physics backend to reset the vehicle. If not input data is received after 10 seconds ArduPilot will re-send the output frame without incrementing the counter. This allows the physics model to be restarted and re-connect. Note that this may fill up the input buffer of the physics backend after some time. Speed up is the desired speed up as set with the SIM_SPEEDUP param, this is a target only. PWM is a array of 16 servo values in micro seconds, typically in the 1000 to 2000 range as set by the servo output functions.
|
||||
|
||||
The magic value is a constant of 18458, this is used to confirm the packet is from ArduPilot, in the future this may also be used for protocol versioning.
|
||||
|
||||
The frame rate represents the time step the simulation should take, this can be changed with the SIM_RATE_HZ ArduPilot parameter. The physics backend is free to ignore this value, a maximum time step size would typically be set. The SIM_RATE_HZ should value be kept above the vehicle loop rate, by default this 400hz on copter and quadplanes and 50 hz on plane and rover.
|
||||
|
||||
The frame_count will increment for each output frame sent by ArduPilot, this count can be used to detect lost or duplicate frames. This count will be reset when SITL is re-started allowing the physics backend to reset the vehicle. If not input data is received after 10 seconds ArduPilot will re-send the output frame without incrementing the counter. This allows the physics model to be restarted and re-connect. Note that this may fill up the input buffer of the physics backend after some time.
|
||||
|
||||
PWM is a array of 16 servo values in micro seconds, typically in the 1000 to 2000 range as set by the servo output functions.
|
||||
|
||||
SITL input
|
||||
Data is received from the physics backend in a plain text JSON format. The data must contain the following fields:
|
||||
```
|
||||
timestamp (us) physics time
|
||||
timestamp (s) physics time
|
||||
imu:
|
||||
gyro(roll, pitch, yaw) (radians/sec) body frame
|
||||
accel_body(north, east, down) (m/s^2) body frame
|
||||
accel_body(x, y, z) (m/s^2) body frame
|
||||
|
||||
position(north, east, down) (m) earth frame
|
||||
attitude(roll, pitch yaw) (radians)
|
||||
velocity(north, east,down) (m/s) earth frame
|
||||
velocity(north, east, down) (m/s) earth frame
|
||||
```
|
||||
This is a example input frame, it should be preceded by and terminated with a carriage return ("\n") :
|
||||
```
|
||||
{"timestamp":2500,"imu":{"gyro":[0,0,0],"accel_body":[0,0,0]},"position":[0,0,0],"attitude":[0,0,0],"velocity":[0,0,0]}
|
||||
```
|
||||
The order of fields is not important, this is minimum required fields. In the future a support for a number of additional optional felids will be added to allow readings to be provided for sensors such as airspeed and lidar.
|
||||
The order of fields is not important, this is minimum required fields. In the future a support for a number of additional optional felids will be added to allow readings to be provided for additional sensors such as airspeed and lidar.
|
||||
|
Loading…
Reference in New Issue
Block a user