ardupilot/libraries/SITL/SIM_Webots.h

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

149 lines
4.1 KiB
C
Raw Permalink Normal View History

2019-08-14 09:49:08 -03:00
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
simulator connection for webots simulator https://github.com/omichel/webots
*/
#pragma once
#include <AP_HAL/AP_HAL_Boards.h>
#ifndef HAL_SIM_WEBOTS_ENABLED
#define HAL_SIM_WEBOTS_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
#endif
#if HAL_SIM_WEBOTS_ENABLED
2019-08-14 09:49:08 -03:00
#include <cmath>
2023-12-25 22:21:11 -04:00
#include <AP_HAL/utility/Socket_native.h>
2019-08-14 09:49:08 -03:00
#include "SIM_Aircraft.h"
namespace SITL {
/*
simulation interface
*/
class Webots : public Aircraft {
public:
Webots(const char *frame_str);
/* update model by one time step */
void update(const struct sitl_input &input) override;
/* output servo to simulator */
void output(const struct sitl_input &input);
/* static object creator */
static Aircraft *create(const char *frame_str) {
return NEW_NOTHROW Webots(frame_str);
2019-08-14 09:49:08 -03:00
}
private:
2019-08-14 09:49:08 -03:00
const char *webots_ip = "127.0.0.1";
// assume sensors are streamed on port 5599
uint16_t webots_sensors_port = 5599;
enum {
OUTPUT_ROVER=1,
OUTPUT_QUAD=2,
2019-09-15 16:53:56 -03:00
OUTPUT_TRICOPTER=3,
OUTPUT_PWM=4
2019-08-14 09:49:08 -03:00
} output_type;
bool connect_sockets(void);
bool parse_sensors(const char *json);
bool sensors_receive(void);
void output_rover(const struct sitl_input &input);
void output_quad(const struct sitl_input &input);
2019-09-15 16:53:56 -03:00
void output_tricopter(const struct sitl_input &input);
2019-08-14 09:49:08 -03:00
void output_pwm(const struct sitl_input &input);
void report_FPS();
// buffer for parsing pose data in JSON format
uint8_t sensor_buffer[50000];
uint32_t sensor_buffer_len;
2023-12-25 22:21:11 -04:00
SocketAPM_native *sim_sock;
2019-08-14 09:49:08 -03:00
uint32_t connect_counter;
uint64_t socket_frame_counter;
uint64_t last_socket_frame_counter;
uint64_t frame_counter;
double last_frame_count_s;
enum data_type {
DATA_FLOAT,
DATA_DOUBLE,
DATA_VECTOR3F,
DATA_VECTOR3F_ARRAY,
DATA_FLOAT_ARRAY,
};
struct {
double timestamp;
struct {
Vector3f angular_velocity;
Vector3f linear_acceleration;
Vector3f magnetic_field;
} imu;
struct {
float x, y, z;
} gps;
struct {
float roll, pitch, yaw;
} pose;
struct {
Vector3f world_linear_velocity;
} velocity;
struct {
struct vector3f_array points;
struct float_array ranges;
} scanner;
} state, last_state;
// table to aid parsing of JSON sensor data
struct keytable {
const char *section;
const char *key;
void *ptr;
enum data_type type;
} keytable[13] = {
{ "", "ts", &state.timestamp, DATA_DOUBLE },
{ ".imu", "av", &state.imu.angular_velocity, DATA_VECTOR3F },
{ ".imu", "la", &state.imu.linear_acceleration, DATA_VECTOR3F },
{ ".imu", "mf", &state.imu.magnetic_field, DATA_VECTOR3F },
{ ".gps", "x", &state.gps.x, DATA_FLOAT },
{ ".gps", "y", &state.gps.y, DATA_FLOAT },
{ ".gps", "z", &state.gps.z, DATA_FLOAT },
{ ".pose", "roll", &state.pose.roll, DATA_FLOAT },
{ ".pose", "pitch", &state.pose.pitch, DATA_FLOAT },
{ ".pose", "yaw", &state.pose.yaw, DATA_FLOAT },
{ ".velocity", "wlv", &state.velocity.world_linear_velocity, DATA_VECTOR3F },
{ ".scan", "pl", &state.scanner.points, DATA_VECTOR3F_ARRAY },
{ ".scan", "rl", &state.scanner.ranges, DATA_FLOAT_ARRAY },
};
};
} // namespace SITL
#endif // HAL_SIM_WEBOTS_ENABLED