35 #include <gazebo/gazebo.hh>
36 #include <gazebo/physics/physics.hh>
37 #include <gazebo/sensors/sensors.hh>
40 #include <gazebo/gazebo_config.h>
41 #if GAZEBO_MAJOR_VERSION < 8
42 #error "Paparazzi only supports gazebo versions > 7, please upgrade to a more recent version of Gazebo"
49 #include "generated/airframe.h"
50 #include "generated/flight_plan.h"
62 #if defined(NPS_DEBUG_VIDEO)
64 #include <opencv2/core/core.hpp>
65 #include <opencv2/highgui/highgui.hpp>
66 #include <opencv2/imgproc/imgproc.hpp>
71 #ifndef NPS_GAZEBO_WORLD
72 #define NPS_GAZEBO_WORLD "empty.world"
74 #ifndef NPS_GAZEBO_AC_NAME
75 #define NPS_GAZEBO_AC_NAME "ardrone"
79 #if NPS_SIMULATE_VIDEO
87 struct mt9f002_t mt9f002 __attribute__((weak));
90 static void init_gazebo_video(
void);
91 static void gazebo_read_video(
void);
92 static void read_image(
94 gazebo::sensors::CameraSensorPtr cam);
96 gazebo::sensors::CameraSensorPtr cam;
97 gazebo::common::Time last_measurement_time;
105 #ifndef NPS_MT9F002_SENSOR_RES_DIVIDER
106 #define NPS_MT9F002_SENSOR_RES_DIVIDER 1
108 #endif // NPS_SIMULATE_VIDEO
121 #if NPS_SIMULATE_LASER_RANGE_ARRAY
126 static void gazebo_init_range_sensors(
void);
127 static void gazebo_read_range_sensors(
void);
131 std::shared_ptr<gazebo::sensors::SonarSensor>
sonar = NULL;
138 static gazebo::physics::ModelPtr
model = NULL;
141 static gazebo::sensors::ContactSensorPtr
ct;
146 static void gazebo_write(
double act_commands[],
int commands_nb);
152 ecef_p.
x = ecef_i.X();
153 ecef_p.
y = ecef_i.Y();
154 ecef_p.
z = ecef_i.Z();
170 lla_p.
lat = lla_i.X();
171 lla_p.
lon = lla_i.Y();
172 lla_p.
alt = lla_i.Z();
179 body_p.
x = body_g.X();
180 body_p.
y = -body_g.Y();
181 body_p.
z = -body_g.Z();
188 body_p.
p = body_g.X();
189 body_p.
q = -body_g.Y();
190 body_p.
r = -body_g.Z();
197 eulers.
psi = -quat.Yaw();
198 eulers.
theta = -quat.Pitch();
199 eulers.
phi = quat.Roll();
206 eulers.
psi = -quat.Yaw() - M_PI / 2;
207 eulers.
theta = -quat.Pitch();
208 eulers.
phi = quat.Roll();
233 #ifdef NPS_ACTUATOR_TIME_CONSTANTS
239 #ifdef NPS_ACTUATOR_MAX_ANGULAR_MOMENTUM
241 const float Iwmax[
NPS_COMMANDS_NB] = NPS_ACTUATOR_MAX_ANGULAR_MOMENTUM;
257 bool launch __attribute__((unused)),
258 double *act_commands,
270 #if NPS_SIMULATE_VIDEO
273 #if NPS_SIMULATE_LASER_RANGE_ARRAY
274 gazebo_init_range_sensors();
280 gazebo::runWorld(
model->GetWorld(), 1);
281 gazebo::sensors::run_once();
284 #if NPS_SIMULATE_VIDEO
287 #if NPS_SIMULATE_LASER_RANGE_ARRAY
288 gazebo_read_range_sensors();
296 double speed __attribute__((unused)),
297 double dir __attribute__((unused)))
302 double wind_north __attribute__((unused)),
303 double wind_east __attribute__((unused)),
304 double wind_down __attribute__((unused)))
309 double wind_speed __attribute__((unused)),
310 int turbulence_severity __attribute__((unused)))
316 double temp __attribute__((unused)),
317 double h __attribute__((unused)))
335 string gazebo_home =
"/conf/simulator/gazebo/";
336 string pprz_home(getenv(
"PAPARAZZI_HOME"));
337 string gazebodir = pprz_home + gazebo_home;
338 cout <<
"Gazebo directory: " << gazebodir << endl;
340 if (getenv(
"ROS_MASTER_URI")) {
342 cout <<
"Add ROS plugins... ";
343 gazebo::addPlugin(
"libgazebo_ros_paths_plugin.so");
344 gazebo::addPlugin(
"libgazebo_ros_api_plugin.so");
345 cout <<
"ok" << endl;
348 if (!gazebo::setupServer(0, NULL)) {
349 cout <<
"Failed to start Gazebo, exiting." << endl;
353 cout <<
"Add Paparazzi paths: " << gazebodir << endl;
354 gazebo::common::SystemPaths::Instance()->AddModelPaths(gazebodir +
"models/");
355 sdf::addURIPath(
"model://", gazebodir +
"models/");
356 sdf::addURIPath(
"world://", gazebodir +
"world/");
358 cout <<
"Add TU Delft paths: " << pprz_home +
"/sw/ext/tudelft_gazebo_models/" << endl;
359 gazebo::common::SystemPaths::Instance()->AddModelPaths(pprz_home +
"/sw/ext/tudelft_gazebo_models/models/");
360 sdf::addURIPath(
"model://", pprz_home +
"/sw/ext/tudelft_gazebo_models/models/");
361 sdf::addURIPath(
"world://", pprz_home +
"/sw/ext/tudelft_gazebo_models/world/");
365 string vehicle_filename = sdf::findFile(vehicle_uri,
false);
366 if (vehicle_filename.empty()) {
367 cout <<
"ERROR, could not find vehicle " + vehicle_uri << endl;
370 cout <<
"Load vehicle: " << vehicle_filename << endl;
371 sdf::SDFPtr vehicle_sdf(
new sdf::SDF());
373 if (!sdf::readFile(vehicle_filename, vehicle_sdf)) {
374 cout <<
"ERROR, could not read vehicle " + vehicle_filename << endl;
379 #if NPS_SIMULATE_VIDEO
381 sdf::ElementPtr link = vehicle_sdf->Root()->GetFirstElement()->GetElement(
"link");
383 if (link->Get<
string>(
"name") ==
"front_camera" && link->GetElement(
"sensor")->Get<
string>(
"name") ==
"mt9f002") {
384 if (NPS_MT9F002_SENSOR_RES_DIVIDER != 1) {
385 int w = link->GetElement(
"sensor")->GetElement(
"camera")->GetElement(
"image")->GetElement(
"width")->Get<
int>();
386 int h = link->GetElement(
"sensor")->GetElement(
"camera")->GetElement(
"image")->GetElement(
"height")->Get<
int>();
387 int env = link->GetElement(
"sensor")->GetElement(
"camera")->GetElement(
"lens")->GetElement(
"env_texture_size")->Get<
int>();
388 link->GetElement(
"sensor")->GetElement(
"camera")->GetElement(
"image")->GetElement(
"width")->Set(w / NPS_MT9F002_SENSOR_RES_DIVIDER);
389 link->GetElement(
"sensor")->GetElement(
"camera")->GetElement(
"image")->GetElement(
"height")->Set(h / NPS_MT9F002_SENSOR_RES_DIVIDER);
390 link->GetElement(
"sensor")->GetElement(
"camera")->GetElement(
"lens")->GetElement(
"env_texture_size")->Set(env / NPS_MT9F002_SENSOR_RES_DIVIDER);
393 int fps =
Min(
MT9F002_TARGET_FPS, link->GetElement(
"sensor")->GetElement(
"update_rate")->Get<
int>());
394 link->GetElement(
"sensor")->GetElement(
"update_rate")->Set(fps);
396 }
else if (link->Get<
string>(
"name") ==
"bottom_camera" && link->GetElement(
"sensor")->Get<
string>(
"name") ==
"mt9v117") {
398 int fps =
Min(
MT9V117_TARGET_FPS, link->GetElement(
"sensor")->GetElement(
"update_rate")->Get<
int>());
399 link->GetElement(
"sensor")->GetElement(
"update_rate")->Set(fps);
402 link = link->GetNextElement(
"link");
407 #if NPS_SIMULATE_LASER_RANGE_ARRAY
408 vehicle_sdf->Root()->GetFirstElement()->AddElement(
"include")->GetElement(
"uri")->Set(
"model://range_sensors");
409 sdf::ElementPtr range_joint = vehicle_sdf->Root()->GetFirstElement()->AddElement(
"joint");
410 range_joint->GetAttribute(
"name")->Set(
"range_sensor_joint");
411 range_joint->GetAttribute(
"type")->Set(
"fixed");
412 range_joint->GetElement(
"parent")->Set(
"chassis");
413 range_joint->GetElement(
"child")->Set(
"range_sensors::base");
418 string world_filename = sdf::findFile(world_uri,
false);
419 if (world_filename.empty()) {
420 cout <<
"ERROR, could not find world " + world_uri << endl;
423 cout <<
"Load world: " << world_filename << endl;
424 sdf::SDFPtr world_sdf(
new sdf::SDF());
426 if (!sdf::readFile(world_filename, world_sdf)) {
427 cout <<
"ERROR, could not read world " + world_filename << endl;
432 world_sdf->Root()->GetFirstElement()->InsertElement(vehicle_sdf->Root()->GetFirstElement());
434 world_sdf->Write(pprz_home +
"/var/gazebo.world");
436 gazebo::physics::WorldPtr world = gazebo::loadWorld(pprz_home +
"/var/gazebo.world");
438 cout <<
"Failed to open world, exiting." << endl;
451 gazebo::sensors::run_once(
true);
452 gazebo::sensors::run_threads();
453 gazebo::runWorld(world, 1);
454 cout <<
"Sensors initialized..." << endl;
458 gazebo::sensors::SensorManager *mgr = gazebo::sensors::SensorManager::Instance();
459 ct = static_pointer_cast < gazebo::sensors::ContactSensor > (mgr->GetSensor(
"contactsensor"));
462 sonar = static_pointer_cast<gazebo::sensors::SonarSensor>(mgr->GetSensor(
"sonarsensor"));
464 cout <<
"Found sonar" << endl;
467 gazebo::physics::LinkPtr sonar_link =
model->GetLink(
"sonar");
470 if (sonar_link->GetSensorCount() != 1) {
471 cout <<
"ERROR: Link '" << sonar_link->GetName()
472 <<
"' should only contain 1 sensor!" << endl;
474 string name = sonar_link->GetSensorName(0);
475 sonar = static_pointer_cast< gazebo::sensors::SonarSensor > (mgr->GetSensor(name));
477 cout <<
"ERROR: Could not get pointer to '" << name <<
"'!" << endl;
480 sonar->SetActive(
true);
486 #ifdef MOTOR_MIXING_YAW_COEF
487 const double yaw_coef[] = MOTOR_MIXING_YAW_COEF;
490 gazebo_actuators.
torques[i] = -fabs(gazebo_actuators.
torques[i]) * yaw_coef[i] / fabs(yaw_coef[i]);
494 cout <<
"Gazebo initialized successfully!" << endl;
507 static ignition::math::Vector3d vel_prev;
508 static double time_prev;
510 gazebo::physics::WorldPtr world =
model->GetWorld();
511 ignition::math::Pose3d pose =
model->WorldPose();
512 ignition::math::Vector3d vel =
model->WorldLinearVel();
513 ignition::math::Vector3d ang_vel =
model->WorldAngularVel();
514 gazebo::common::SphericalCoordinatesPtr sphere = world->SphericalCoords();
515 ignition::math::Quaterniond local_to_global_quat(0, 0, -sphere->HeadingOffset().Radian());
518 fdm.
time = world->SimTime().Double();
524 double dt =
fdm.
time - time_prev;
525 ignition::math::Vector3d accel = (vel - vel_prev) / dt;
536 gazebo::common::SphericalCoordinates::ECEF));
538 gazebo::common::SphericalCoordinates::GLOBAL));
539 fdm.
lla_pos =
to_pprz_lla(sphere->PositionTransform(pose.Pos(), gazebo::common::SphericalCoordinates::LOCAL,
540 gazebo::common::SphericalCoordinates::SPHERICAL));
549 double agl =
sonar->Range();
550 if (agl >
sonar->RangeMax()) agl = -1.0;
558 gazebo::common::SphericalCoordinates::ECEF));
561 gazebo::common::SphericalCoordinates::GLOBAL));
566 gazebo::common::SphericalCoordinates::ECEF));
569 gazebo::common::SphericalCoordinates::GLOBAL));
589 fdm.
ltp_g =
to_pprz_ltp(sphere->VelocityTransform(-1 * world->Gravity(), gazebo::common::SphericalCoordinates::LOCAL,
590 gazebo::common::SphericalCoordinates::GLOBAL));
591 fdm.
ltp_h =
to_pprz_ltp(sphere->VelocityTransform(world->MagneticField(), gazebo::common::SphericalCoordinates::LOCAL,
592 gazebo::common::SphericalCoordinates::GLOBAL));
595 #if GAZEBO_MAJOR_VERSION >= 8 && 0 // TODO implement
639 for (
int i = 0; i < commands_nb; ++i) {
644 #ifdef NPS_ACTUATOR_TIME_CONSTANTS
650 double thrust = gazebo_actuators.
thrusts[i] * u;
651 double torque = gazebo_actuators.
torques[i] * u;
653 #ifdef NPS_ACTUATOR_MAX_ANGULAR_MOMENTUM
656 double spinup_torque = gazebo_actuators.
max_ang_momentum[i] / (2.0 * sqrt(u > 0.05 ? u : 0.05)) * udot;
657 torque += spinup_torque;
661 gazebo::physics::LinkPtr link =
model->GetLink(gazebo_actuators.
names[i]);
662 link->AddRelativeForce(ignition::math::Vector3d(0, 0, thrust));
663 link->AddRelativeTorque(ignition::math::Vector3d(0, 0, torque));
667 #if NPS_SIMULATE_VIDEO
682 static void init_gazebo_video(
void)
684 gazebo::sensors::SensorManager *mgr = gazebo::sensors::SensorManager::Instance();
686 cout <<
"Initializing cameras..." << endl;
691 gazebo::physics::LinkPtr link =
model->GetLink(
cameras[i]->dev_name);
699 if (link->GetSensorCount() != 1) {
700 cout <<
"ERROR: Link '" << link->GetName()
701 <<
"' should only contain 1 sensor!" << endl;
704 string name = link->GetSensorName(0);
705 gazebo::sensors::CameraSensorPtr cam = static_pointer_cast
706 < gazebo::sensors::CameraSensor > (mgr->GetSensor(name));
708 cout <<
"ERROR: Could not get pointer to '" << name <<
"'!" << endl;
712 cam->SetActive(
true);
715 gazebo_cams[i].cam = cam;
716 gazebo_cams[i].last_measurement_time = cam->LastMeasurementTime();
732 if (cam->Name() ==
"mt9f002") {
748 }
else if (cam->Name() ==
"mt9v117") {
759 cout <<
"ok" << endl;
771 static void gazebo_read_video(
void)
774 gazebo::sensors::CameraSensorPtr &cam = gazebo_cams[i].cam;
776 if (cam == NULL) {
continue; }
779 if ((cam->LastMeasurementTime() - gazebo_cams[i].last_measurement_time).Float() < 0.005
780 || cam->LastMeasurementTime() == 0) {
continue; }
783 read_image(&img, cam);
786 cv::Mat RGB_cam(cam->ImageHeight(), cam->ImageWidth(), CV_8UC3, (
uint8_t *)cam->ImageData());
787 cv::cvtColor(RGB_cam, RGB_cam, cv::COLOR_RGB2BGR);
788 cv::namedWindow(
cameras[i]->dev_name, cv::WINDOW_AUTOSIZE);
789 cv::imshow(
cameras[i]->dev_name, RGB_cam);
797 gazebo_cams[i].last_measurement_time = cam->LastMeasurementTime();
811 static void read_image(
struct image_t *img, gazebo::sensors::CameraSensorPtr cam)
813 bool is_mt9f002 =
false;
814 if (cam->Name() ==
"mt9f002") {
822 const uint8_t *data_rgb = cam->ImageData();
824 for (
int x_yuv = 0; x_yuv < img->
w; ++x_yuv) {
825 for (
int y_yuv = 0; y_yuv < img->
h; ++y_yuv) {
836 int idx_rgb = 3 * (cam->ImageWidth() * y_rgb + x_rgb);
837 int idx_yuv = 2 * (img->
w * y_yuv + x_yuv);
838 int idx_px = img->
w * y_yuv + x_yuv;
839 if (idx_px % 2 == 0) {
840 data_yuv[idx_yuv] = - 0.148 * data_rgb[idx_rgb]
841 - 0.291 * data_rgb[idx_rgb + 1]
842 + 0.439 * data_rgb[idx_rgb + 2] + 128;
844 data_yuv[idx_yuv] = 0.439 * data_rgb[idx_rgb]
845 - 0.368 * data_rgb[idx_rgb + 1]
846 - 0.071 * data_rgb[idx_rgb + 2] + 128;
848 data_yuv[idx_yuv + 1] = 0.257 * data_rgb[idx_rgb]
849 + 0.504 * data_rgb[idx_rgb + 1]
850 + 0.098 * data_rgb[idx_rgb + 2] + 16;
854 gazebo::common::Time
ts = cam->LastMeasurementTime();
855 img->
ts.tv_sec = ts.sec;
856 img->
ts.tv_usec = ts.nsec / 1000.0;
857 img->
pprz_ts = ts.Double() * 1e6;
862 #if NPS_SIMULATE_LASER_RANGE_ARRAY
885 struct gazebo_ray_t {
886 gazebo::sensors::RaySensorPtr sensor;
887 gazebo::common::Time last_measurement_time;
890 static struct gazebo_ray_t rays[LASER_RANGE_ARRAY_NUM_SENSORS] = {{NULL, 0}};
891 static float range_orientation[] = LASER_RANGE_ARRAY_ORIENTATIONS;
892 static uint8_t ray_sensor_agl_index = 255;
894 #define VL53L0_MAX_VAL 8.191f
896 static void gazebo_init_range_sensors(
void)
898 gazebo::sensors::SensorManager *mgr = gazebo::sensors::SensorManager::Instance();
899 gazebo::sensors::Sensor_V
sensors = mgr->GetSensors();
903 gazebo::sensors::RaySensorPtr ray_sensor;
904 uint8_t ray_sensor_count_selected = 0;
907 for (
uint16_t i = 0; i < sensor_count; i++) {
908 if (ray_sensor_count_selected > LASER_RANGE_ARRAY_NUM_SENSORS) {
912 if (sensors.at(i)->Type() ==
"ray") {
913 ray_sensor = static_pointer_cast<gazebo::sensors::RaySensor>(sensors.at(i));
916 cout <<
"ERROR: Could not get pointer to raysensor " << i <<
"!" << endl;
929 for (
int j = 0; j < LASER_RANGE_ARRAY_NUM_SENSORS; j++) {
930 struct DoubleEulers def = {0, range_orientation[j * 2], range_orientation[j * 2 + 1]};
935 if (fabs(angle) < RadOfDeg(5)) {
936 ray_sensor_count_selected++;
937 rays[j].sensor = ray_sensor;
938 rays[j].sensor->SetActive(
true);
940 #if LASER_RANGE_ARRAY_SEND_AGL
942 if (fabs(range_orientation[j * 2] + M_PI_2) < RadOfDeg(5)) {
943 ray_sensor_agl_index = j;
952 if (ray_sensor_count_selected != LASER_RANGE_ARRAY_NUM_SENSORS) {
953 cout <<
"ERROR: you have defined " << LASER_RANGE_ARRAY_NUM_SENSORS <<
" sensors in your airframe file, but only "
954 << ray_sensor_count_selected <<
" sensors have been found in the gazebo simulator, "
955 "with the same orientation as in the airframe file " << endl;
958 cout <<
"Initialized laser range array" << endl;
961 static void gazebo_read_range_sensors(
void)
966 for (
int i = 0; i < LASER_RANGE_ARRAY_NUM_SENSORS; i++) {
967 if ((rays[i].sensor->LastMeasurementTime() - rays[i].last_measurement_time).Float() < 0.005
968 || rays[i].sensor->LastMeasurementTime() == 0) {
continue; }
970 if (rays[i].sensor->Range(0) < 1e-5 || rays[i].sensor->Range(0) >
VL53L0_MAX_VAL) {
973 range = rays[i].sensor->Range(0);
976 range_orientation[i * 2 + 1]);
978 if (i == ray_sensor_agl_index) {
980 float agl = rays[i].sensor->Range(0);
982 if (agl > 1e-5 && !isinf(agl)) {
986 rays[i].last_measurement_time = rays[i].sensor->LastMeasurementTime();
989 #endif // NPS_SIMULATE_LASER_RANGE_ARRAY
991 #pragma GCC diagnostic pop // Ignore -Wdeprecated-declarations
struct NedCoor_d to_pprz_ned(ignition::math::Vector3d global)
vector in North East Down coordinates Units: meters
struct NedCoor_d ltpprz_ecef_accel
accel in ltppprz frame, wrt ECEF frame
struct LlaCoor_d lla_pos_geoc
void nps_fdm_set_temperature(double temp, double h)
Set temperature in degrees Celcius at given height h above MSL.
struct DoubleVect3 body_inertial_accel
acceleration in body frame, wrt ECI inertial frame
float focal_x
focal length in the x-direction in pixels
struct crop_t crop
Cropped area definition.
struct gazebo_actuators_t gazebo_actuators
struct DoubleRates body_ecef_rotvel
#define MT9V117_TARGET_FPS
#define QUAT_DOT_PRODUCT(_qa, _qb)
uint16_t h
height of the cropped area
static void gazebo_write(double act_commands[], int commands_nb)
Write actuator commands to Gazebo.
struct img_size_t output_size
Output image size.
#define OBS_DETECTION_RANGE_ARRAY_NPS_ID
static gazebo::physics::ModelPtr model
#define NPS_COMMANDS_NB
Number of commands sent to the FDM of NPS.
#define MT9F002_OUTPUT_HEIGHT
Simple first order low pass filter with bilinear transform.
struct EcefCoor_d to_pprz_ecef(ignition::math::Vector3d ecef_i)
void image_free(struct image_t *img)
Free the image.
struct NedCoor_d ltp_ecef_accel
acceleration in LTP frame, wrt ECEF frame
Initialization and configuration of the MT9V117 CMOS Chip.
double alt
in meters above WGS84 reference ellipsoid
static float pprz_isa_pressure_of_height(float height, float ref_p)
Get pressure in Pa from height (using simplified equation).
struct NpsFdm fdm
Holds all necessary NPS FDM state information.
Main include for ABI (AirBorneInterface).
static struct video_config_t * cameras[VIDEO_THREAD_MAX_CAMERAS]
void image_create(struct image_t *img, uint16_t width, uint16_t height, enum image_type type)
Create a new image.
double thrusts[NPS_COMMANDS_NB]
struct LlaCoor_d lla_pos_pprz
First order low pass filter structure.
vector in Latitude, Longitude and Altitude
#define AGL_RAY_SENSOR_GAZEBO_ID
char * dev_name
path to device
struct DoubleRates body_inertial_rotvel
void nps_fdm_init(double dt)
Initialize actuator dynamics, set unused fields in fdm.
static void init_first_order_high_pass(struct FirstOrderHighPass *filter, float tau, float sample_time, float value)
Init first order high pass filter.
void nps_fdm_set_wind_ned(double wind_north, double wind_east, double wind_down)
uint32_t pprz_ts
The timestamp in us since system startup.
struct DoubleEulers ltp_to_body_eulers
uint16_t offset_x
Offset from left in pixels.
static float update_first_order_high_pass(struct FirstOrderHighPass *filter, float value)
Update first order high pass filter state with a new value.
struct NedCoor_d ltp_ecef_vel
velocity in LTP frame, wrt ECEF frame
struct pprz_autopilot autopilot
Global autopilot structure.
double pressure_sl
pressure at sea level in Pascal
First order high pass filter structure.
struct NedCoor_d ltpprz_pos
uint16_t w
Width of the cropped area.
struct LlaCoor_d to_pprz_lla(ignition::math::Vector3d lla_i)
struct EcefCoor_d ecef_ecef_vel
velocity in ECEF frame, wrt ECEF frame
uint8_t buf_idx
Buffer index for V4L2 freeing.
double airspeed
equivalent airspeed in m/s
Image helper functions like resizing, color filter, converters...
struct DoubleVect3 to_pprz_body(ignition::math::Vector3d body_g)
struct DoubleVect3 body_accel
acceleration in body frame as measured by an accelerometer (incl.
double pressure
current (static) atmospheric pressure in Pascal
void nps_fdm_set_turbulence(double wind_speed, int turbulence_severity)
string names[NPS_COMMANDS_NB]
Architecture independent timing functions.
void double_quat_of_eulers(struct DoubleQuat *q, struct DoubleEulers *e)
struct img_size_t sensor_size
Original sensor size.
Paparazzi atmospheric pressure conversion utilities.
Computer vision framework for onboard processing.
struct DoubleVect3 wind
velocity in m/s in NED
struct DoubleRates to_pprz_rates(ignition::math::Vector3d body_g)
void * buf
Image buffer (depending on the image_type)
struct LlaCoor_d lla_pos_geod
struct DoubleEulers to_global_pprz_eulers(ignition::math::Quaterniond quat)
double torques[NPS_COMMANDS_NB]
struct NpsSensors sensors
double dynamic_pressure
dynamic pressure in Pascal
void nps_fdm_run_step(bool launch, double *act_commands, int commands_nb)
Update the simulation state.
vector in EarthCenteredEarthFixed coordinates
This header gives NPS access to the list of added cameras.
#define NPS_GAZEBO_AC_NAME
#define MT9F002_OUTPUT_WIDTH
static const int32_t yaw_coef[MOTOR_MIXING_NB_MOTOR]
Core autopilot interface common to all firmwares.
Initialization and configuration of the MT9F002 CMOS Chip.
struct DoubleVect3 body_ecef_vel
velocity in body frame, wrt ECEF frame
uint16_t offset_y
Offset from top in pixels.
double max_ang_momentum[NPS_COMMANDS_NB]
static void init_gazebo(void)
Set up a Gazebo server.
void cv_run_device(struct video_config_t *device, struct image_t *img)
static void h(const real32_T x[7], const real32_T q[4], real32_T y[6])
struct DoubleVect3 to_pprz_ltp(ignition::math::Vector3d xyz)
struct FirstOrderLowPass lowpass[NPS_COMMANDS_NB]
double temperature
current temperature in degrees Celcius
bool motors_on
motor status
struct timeval ts
The timestamp of creation.
struct DoubleEulers to_pprz_eulers(ignition::math::Quaterniond quat)
struct DoubleQuat ltpprz_to_body_quat
Simple high pass filter with double precision.
float focal_y
focal length in the y-direction in pixels
#define CFG_MT9F002_PIXEL_ARRAY_WIDTH
float center_y
center image coordinate in the y-direction
struct camera_intrinsics_t camera_intrinsics
Intrinsics of the camera; camera calibration parameters and distortion parameter(s) ...
struct EcefCoor_d ecef_pos
static void init_first_order_low_pass(struct FirstOrderLowPass *filter, float tau, float sample_time, float value)
Init first order low pass filter.
UYVY format (uint16 per pixel)
struct DoubleVect3 body_ecef_accel
acceleration in body frame, wrt ECEF frame
#define VIDEO_THREAD_MAX_CAMERAS
void nps_fdm_set_wind(double speed, double dir)
static void gazebo_read(void)
Read Gazebo's simulation state and store the results in the fdm struct used by NPS.
Paparazzi double precision floating point algebra.
struct NedCoor_d ltpprz_ecef_vel
velocity in ltppprz frame, wrt ECEF frame
uint32_t get_sys_time_usec(void)
Get the time in microseconds since startup.
std::shared_ptr< gazebo::sensors::SonarSensor > sonar
static bool gazebo_initialized
#define MT9F002_TARGET_FPS
static gazebo::sensors::ContactSensorPtr ct
#define CFG_MT9F002_PIXEL_ARRAY_HEIGHT
struct DoubleQuat ltp_to_body_quat
double sideslip
sideslip angle in rad
struct EcefCoor_d ecef_ecef_accel
acceleration in ECEF frame, wrt ECEF frame
Common Motor Mixing configuration types.
struct DoubleEulers ltpprz_to_body_eulers
struct FirstOrderHighPass highpass[NPS_COMMANDS_NB]
double aoa
angle of attack in rad
static float update_first_order_low_pass(struct FirstOrderLowPass *filter, float value)
Update first order low pass filter state with a new value.
float center_x
center image coordinate in the x-direction