Paparazzi UAS  v5.8.2_stable-0-g6260b7c
Paparazzi is a free software Unmanned Aircraft System.
 All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
ins_vectornav.c
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2015 Michal Podhradsky, michal.podhradsky@aggiemail.usu.edu
3  * Utah State University, http://aggieair.usu.edu/
4  *
5  * This file is part of paparazzi.
6  *
7  * paparazzi is free software; you can redistribute it and/or modify
8  * it under the terms of the GNU General Public License as published by
9  * the Free Software Foundation; either version 2, or (at your option)
10  * any later version.
11  *
12  * paparazzi is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with paparazzi; see the file COPYING. If not, write to
19  * the Free Software Foundation, 59 Temple Place - Suite 330,
20  * Boston, MA 02111-1307, USA.
21  */
30 
32 
33 #if PERIODIC_TELEMETRY
35 
36 static void send_ins(struct transport_tx *trans, struct link_device *dev)
37 {
38  pprz_msg_send_INS(trans, dev, AC_ID,
42 }
43 
44 static void send_ins_z(struct transport_tx *trans, struct link_device *dev)
45 {
46  pprz_msg_send_INS_Z(trans, dev, AC_ID,
48 }
49 
50 static void send_ins_ref(struct transport_tx *trans, struct link_device *dev)
51 {
52  if (ins_vn.ltp_initialized) {
53  pprz_msg_send_INS_REF(trans, dev, AC_ID,
57  }
58 }
59 
60 static void send_vn_info(struct transport_tx *trans, struct link_device *dev)
61 {
62  pprz_msg_send_VECTORNAV_INFO(trans, dev, AC_ID,
67  &ins_vn.mode,
68  &ins_vn.err,
69  &ins_vn.ypr_u.phi,
71  &ins_vn.ypr_u.psi);
72 }
73 
74 static void send_accel(struct transport_tx *trans, struct link_device *dev)
75 {
76  pprz_msg_send_IMU_ACCEL(trans, dev, AC_ID,
78 }
79 
80 static void send_gyro(struct transport_tx *trans, struct link_device *dev)
81 {
82  pprz_msg_send_IMU_GYRO(trans, dev, AC_ID,
84 }
85 
86 static void send_accel_scaled(struct transport_tx *trans, struct link_device *dev)
87 {
88  pprz_msg_send_IMU_ACCEL_SCALED(trans, dev, AC_ID,
90 }
91 
92 static void send_gyro_scaled(struct transport_tx *trans, struct link_device *dev)
93 {
94  pprz_msg_send_IMU_GYRO_SCALED(trans, dev, AC_ID,
96 }
97 #endif
98 
99 #ifndef USE_INS_NAV_INIT
100 #define USE_INS_NAV_INIT TRUE
101 PRINT_CONFIG_MSG("USE_INS_NAV_INIT defaulting to TRUE");
102 #endif
103 
108 {
109  // receive data
111 
112  // read message
116  }
117 }
118 
119 
124 {
125  // Initialize variables
128 
129  // Initialize packet
138 
142 
146 
147 #if USE_INS_NAV_INIT
150 #else
152 #endif
153 
154  struct FloatEulers body_to_imu_eulers =
156  orientationSetEulers_f(&ins_vn.body_to_imu, &body_to_imu_eulers);
157 
158 #if PERIODIC_TELEMETRY
159  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_INS, send_ins);
160  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_INS_Z, send_ins_z);
161  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_INS_REF, send_ins_ref);
162  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_VECTORNAV_INFO, send_vn_info);
163  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_ACCEL, send_accel);
164  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_GYRO, send_gyro);
165  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_ACCEL_SCALED, send_accel_scaled);
166  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_GYRO_SCALED, send_gyro_scaled);
167 #endif
168 }
169 
174 {
176 
177  uint16_t idx = VN_HEADER_SIZE;
178 
179  // Timestamp [nanoseconds] since startup
180  static uint64_t nanostamp = 0;
181  memcpy(&nanostamp, &ins_vn.vn_packet.msg_buf[idx], sizeof(uint64_t));
182  idx += sizeof(uint64_t);
183 
184  // Timestamp [s]
185  ins_vn.timestamp = ((float)nanostamp / 1000000000); // [nanoseconds to seconds]
186 
187  //Attitude, float, [degrees], yaw, pitch, roll, NED frame
188  memcpy(&ins_vn.attitude, &ins_vn.vn_packet.msg_buf[idx], 3 * sizeof(float));
189  idx += 3 * sizeof(float);
190 
191  // Rates (imu frame), float, [rad/s]
192  memcpy(&ins_vn.gyro, &ins_vn.vn_packet.msg_buf[idx], 3 * sizeof(float));
193  idx += 3 * sizeof(float);
194 
195  //Pos LLA, double,[deg, deg, m]
196  //The estimated position given as latitude, longitude, and altitude given in [deg, deg, m] respectfully.
197  memcpy(&ins_vn.pos_lla, &ins_vn.vn_packet.msg_buf[idx], 3 * sizeof(double));
198  idx += 3 * sizeof(double);
199 
200  //VelNed, float [m/s]
201  //The estimated velocity in the North East Down (NED) frame, given in m/s.
202  memcpy(&ins_vn.vel_ned, &ins_vn.vn_packet.msg_buf[idx], 3 * sizeof(float));
203  idx += 3 * sizeof(float);
204 
205  // Accel (imu-frame), float, [m/s^-2]
206  memcpy(&ins_vn.accel, &ins_vn.vn_packet.msg_buf[idx], 3 * sizeof(float));
207  idx += 3 * sizeof(float);
208 
209  // tow (in nanoseconds), uint64
210  static uint64_t tow = 0;
211  memcpy(&tow, &ins_vn.vn_packet.msg_buf[idx], sizeof(uint64_t));
212  idx += sizeof(uint64_t);
213  tow = tow / 1000000; // nanoseconds to miliseconds
214  gps.tow = (uint32_t) tow;
215 
216  //num sats, uint8
218  idx++;
219 
220  //gps fix, uint8
221  gps.fix = ins_vn.vn_packet.msg_buf[idx];
222  idx++;
223 
224  //posU, float[3]
225  memcpy(&ins_vn.pos_u, &ins_vn.vn_packet.msg_buf[idx], 3 * sizeof(float));
226  idx += 3 * sizeof(float);
227 
228  //velU, float
229  memcpy(&ins_vn.vel_u, &ins_vn.vn_packet.msg_buf[idx], sizeof(float));
230  idx += sizeof(float);
231 
232  //linear acceleration imu-body frame, float [m/s^2]
233  //The estimated linear acceleration (without gravity) reported in m/s^2, and given in the body frame. The
234  //acceleration measurement has been bias compensated by the onboard INS filter, and the gravity
235  //component has been removed using the current gravity reference vector model. This measurement is
236  //attitude dependent, since the attitude solution is required to map the gravity reference vector (known
237  //in the inertial NED frame), into the body frame so that it can be removed from the measurement. If the
238  //device is stationary and the onboard INS filter is tracking, the measurement nominally will read 0 in all
239  //three axes.
240  memcpy(&ins_vn.lin_accel, &ins_vn.vn_packet.msg_buf[idx], 3 * sizeof(float));
241  idx += 3 * sizeof(float);
242 
243  //YprU, float[3]
244  memcpy(&ins_vn.ypr_u, &ins_vn.vn_packet.msg_buf[idx], 3 * sizeof(float));
245  idx += 3 * sizeof(float);
246 
247  //instatus, uint16
248  memcpy(&ins_vn.ins_status, &ins_vn.vn_packet.msg_buf[idx], sizeof(uint16_t));
249  idx += sizeof(uint16_t);
250 
251  //Vel body, float [m/s]
252  // The estimated velocity in the body (i.e. imu) frame, given in m/s.
253  memcpy(&ins_vn.vel_body, &ins_vn.vn_packet.msg_buf[idx], sizeof(float));
254  idx += sizeof(float);
255 
256  // Propaget the ins states
258 }
259 
264 {
265  ins_vn.mode = (uint8_t)(ins_vn.ins_status & 0x03);
266  ins_vn.err = (uint8_t)((ins_vn.ins_status >> 3) & 0x0F);
267 }
268 
274 {
275  gps.sacc = (uint32_t)(ins_vn.vel_u * 100);
276 }
277 
283 {
284  float pacc = ins_vn.pos_u[0]; // in meters
285  if (ins_vn.pos_u[1] > pacc) {
286  pacc = ins_vn.pos_u[1];
287  }
288  if (ins_vn.pos_u[2] > pacc) {
289  pacc = ins_vn.pos_u[2];
290  }
291 
292  gps.pacc = (uint32_t)(pacc * 100);
293 }
294 
302 {
303  static struct FloatEulers att_rad;
304  att_rad.phi = RadOfDeg(vn_attitude->psi);
305  att_rad.theta = RadOfDeg(vn_attitude->theta);
306  att_rad.psi = RadOfDeg(vn_attitude->phi);
307 
308  vn_attitude->phi = att_rad.phi;
309  vn_attitude->theta = att_rad.theta;
310  vn_attitude->psi = att_rad.psi;
311 }
312 
318 {
319  // Acceleration [m/s^2]
320  // in fixed point for sending as ABI and telemetry msgs
322 
323  // Rates [rad/s]
324  static struct FloatRates body_rate;
325  // in fixed point for sending as ABI and telemetry msgs
327  float_rmat_ratemult(&body_rate, orientationGetRMat_f(&ins_vn.body_to_imu), &ins_vn.gyro); // compute body rates
328  stateSetBodyRates_f(&body_rate); // Set state [rad/s]
329 
330  // Attitude [deg]
331  ins_vectornav_yaw_pitch_roll_to_attitude(&ins_vn.attitude); // convert to correct units and axis [rad]
332  static struct FloatQuat imu_quat; // convert from euler to quat
333  float_quat_of_eulers(&imu_quat, &ins_vn.attitude);
334  static struct FloatRMat imu_rmat; // convert from quat to rmat
335  float_rmat_of_quat(&imu_rmat, &imu_quat);
336  static struct FloatRMat ltp_to_body_rmat; // rotate to body frame
337  float_rmat_comp(&ltp_to_body_rmat, &imu_rmat, orientationGetRMat_f(&ins_vn.body_to_imu));
338  stateSetNedToBodyRMat_f(&ltp_to_body_rmat); // set body states [rad]
339 
340  // NED (LTP) velocity [m/s]
341  // North east down (NED), also known as local tangent plane (LTP),
342  // is a geographical coordinate system for representing state vectors that is commonly used in aviation.
343  // It consists of three numbers: one represents the position along the northern axis,
344  // one along the eastern axis, and one represents vertical position. Down is chosen as opposed to
345  // up in order to comply with the right-hand rule.
346  // The origin of this coordinate system is usually chosen to be the aircraft's center of gravity.
347  // x = North
348  // y = East
349  // z = Down
350  stateSetSpeedNed_f(&ins_vn.vel_ned); // set state
351 
352  // NED (LTP) acceleration [m/s^2]
353  static struct FloatVect3 accel_meas_ltp;// first we need to rotate linear acceleration from imu-frame to body-frame
355  static struct NedCoor_f ltp_accel; // assign to NedCoord_f struct
356  VECT3_ASSIGN(ltp_accel, accel_meas_ltp.x, accel_meas_ltp.y, accel_meas_ltp.z);
357  stateSetAccelNed_f(&ltp_accel); // then set the states
358  ins_vn.ltp_accel_f = ltp_accel;
359 
360  // LLA position [rad, rad, m]
361  //static struct LlaCoor_f lla_pos; // convert from deg to rad, and from double to float
362  ins_vn.lla_pos.lat = RadOfDeg((float)ins_vn.pos_lla[0]); // ins_impl.pos_lla[0] = lat
363  ins_vn.lla_pos.lon = RadOfDeg((float)ins_vn.pos_lla[1]); // ins_impl.pos_lla[1] = lon
364  ins_vn.lla_pos.alt = ((float)ins_vn.pos_lla[2]); // ins_impl.pos_lla[2] = alt
367 
368  // ECEF position
369  struct LtpDef_f def;
371  struct EcefCoor_f ecef_vel;
372  ecef_of_ned_point_f(&ecef_vel, &def, &ins_vn.vel_ned);
373  ECEF_BFP_OF_REAL(gps.ecef_vel, ecef_vel);
374 
375  // ECEF velocity
379 
380 
381 #if GPS_USE_LATLONG
382  // GPS UTM
383  /* Computes from (lat, long) in the referenced UTM zone */
384  struct UtmCoor_f utm_f;
385  utm_f.zone = nav_utm_zone0;
386  /* convert to utm */
387  //utm_of_lla_f(&utm_f, &lla_f);
388  utm_of_lla_f(&utm_f, &ins_vn.lla_pos);
389  /* copy results of utm conversion */
390  gps.utm_pos.east = (int32_t)(utm_f.east * 100);
391  gps.utm_pos.north = (int32_t)(utm_f.north * 100);
392  gps.utm_pos.alt = (int32_t)(utm_f.alt * 1000);
394 #endif
395 
396  // GPS Ground speed
397  float speed = sqrt(ins_vn.vel_ned.x * ins_vn.vel_ned.x + ins_vn.vel_ned.y * ins_vn.vel_ned.y);
398  gps.gspeed = ((uint16_t)(speed * 100));
399 
400  // GPS course
401  gps.course = (int32_t)(1e7 * (atan2(ins_vn.vel_ned.y, ins_vn.vel_ned.x)));
402 
403  // Because we have not HMSL data from Vectornav, we are using LLA-Altitude
404  // as a workaround
406 
407  // set position uncertainty
409 
410  // set velocity uncertainty
412 
413  // check GPS status
416  if (gps.fix == GPS_FIX_3D) {
419  }
420 
421  // read INS status
423 
424  // update internal states for telemetry purposes
425  // TODO: directly convert vectornav output instead of using state interface
426  // to support multiple INS running at the same time
430 
431  // send ABI messages
432  uint32_t now_ts = get_sys_time_usec();
433  AbiSendMsgGPS(GPS_UBX_ID, now_ts, &gps);
434  AbiSendMsgIMU_GYRO_INT32(IMU_ASPIRIN_ID, now_ts, &ins_vn.gyro_i);
435  AbiSendMsgIMU_ACCEL_INT32(IMU_ASPIRIN_ID, now_ts, &ins_vn.accel_i);
436 }
437 
438 
443 {
444  struct LlaCoor_i llh_nav0; /* Height above the ellipsoid */
445  llh_nav0.lat = NAV_LAT0;
446  llh_nav0.lon = NAV_LON0;
447  /* NAV_ALT0 = ground alt above msl, NAV_MSL0 = geoid-height (msl) over ellipsoid */
448  llh_nav0.alt = NAV_ALT0 + NAV_MSL0;
449 
450  struct EcefCoor_i ecef_nav0;
451  ecef_of_lla_i(&ecef_nav0, &llh_nav0);
452 
453  ltp_def_from_ecef_i(&ins_vn.ltp_def, &ecef_nav0);
454  ins_vn.ltp_def.hmsl = NAV_ALT0;
456 }
double pos_lla[3]
unsigned short uint16_t
Definition: types.h:16
struct NedCoor_f ltp_accel_f
Definition: ins_vectornav.h:82
#define VN_HEADER_SIZE
Definition: vn200_serial.h:43
int32_t z
in centimeters
int32_t north
in centimeters
#define RATES_BFP_OF_REAL(_ri, _rf)
Definition: pprz_algebra.h:698
static void stateSetNedToBodyRMat_f(struct FloatRMat *ned_to_body_rmat)
Set vehicle body attitude from rotation matrix (float).
Definition: state.h:1070
uint16_t overrun_error
Definition: vn200_serial.h:63
#define ECEF_BFP_OF_REAL(_o, _i)
void float_quat_of_eulers(struct FloatQuat *q, struct FloatEulers *e)
Quaternion from Euler angles.
void ins_vectornav_propagate()
Propagate the received states into the vehicle state machine.
definition of the local (flat earth) coordinate system
float y
in meters
float east
in meters
uint8_t msg_idx
Definition: vn200_serial.h:61
float phi
in radians
uint32_t pacc
position accuracy in cm
Definition: gps.h:77
Generic transmission transport header.
Definition: transport.h:89
float north
in meters
struct VNPacket vn_packet
Packet struct.
Definition: ins_vectornav.h:89
uint8_t err
see page 122 of VN-200 datasheet
void ins_vectornav_set_sacc(void)
Set speed (velocity) uncertainty (NED) speed accuracy in cm/s.
float alt
in meters above WGS84 reference ellipsoid
#define INS_VN_BODY_TO_IMU_PSI
Definition: ins_vectornav.h:66
struct NedCoor_i ltp_accel_i
Definition: ins_vectornav.h:78
static struct EcefCoor_i * stateGetPositionEcef_i(void)
Get position in ECEF coordinates (int).
Definition: state.h:639
Periodic telemetry system header (includes downlink utility and generated code).
uint32_t chksm_error
Definition: vn200_serial.h:57
vector in EarthCenteredEarthFixed coordinates
vector in EarthCenteredEarthFixed coordinates
int32_t y
in centimeters
void ecef_of_ned_point_f(struct EcefCoor_f *ecef, struct LtpDef_f *def, struct NedCoor_f *ned)
uint16_t counter
Definition: vn200_serial.h:68
struct FloatEulers ypr_u
Attitude uncertainty, 1sigma, float, [degrees], yaw, pitch, roll.
static struct FloatRMat * orientationGetRMat_f(struct OrientationReps *orientation)
Get vehicle body attitude rotation matrix (float).
float r
in rad/s
#define INT32_VECT3_ZERO(_v)
#define VECT3_ASSIGN(_a, _x, _y, _z)
Definition: pprz_algebra.h:124
#define GPS_UBX_ID
enum VNStatus vn_status
VN status.
Definition: ins_vectornav.h:90
uint32_t hdr_error
Definition: vn200_serial.h:58
uint8_t nav_utm_zone0
Definition: common_nav.c:44
float psi
in radians
struct FloatVect3 lin_accel
Linear acceleration in imu frame [m/s^2].
uint16_t noise_error
Definition: vn200_serial.h:64
position in UTM coordinates Units: meters
int32_t east
in centimeters
#define INS_VN_BODY_TO_IMU_THETA
Definition: ins_vectornav.h:65
void ins_init_origin_from_flightplan(void)
initialize the local origin (ltp_def) from flight plan position
bool_t msg_available
Definition: vn200_serial.h:56
struct FloatEulers attitude
Attitude, float, [degrees], yaw, pitch, roll.
Definition: ins_vectornav.h:98
vector in Latitude, Longitude and Altitude
#define GPS_FIX_3D
3D GPS fix
Definition: gps.h:43
float q
in rad/s
float p
in rad/s
Vectornav VN-200 INS subsystem.
#define IMU_ASPIRIN_ID
int32_t z
Down.
struct UtmCoor_i utm_pos
position in UTM (north,east: cm; alt: mm over ellipsoid)
Definition: gps.h:70
static float get_sys_time_float(void)
Get the time in seconds since startup.
Definition: sys_time.h:124
void vn200_event(struct VNPacket *vnp)
Definition: vn200_serial.c:77
struct EcefCoor_i ecef
Reference point in ecef.
int32_t hmsl
Height above mean sea level in mm.
uint32_t last_3dfix_ticks
cpu time ticks at last valid 3D fix
Definition: gps.h:89
struct FloatRates gyro
Rates in the imu frame m/s.
#define FALSE
Definition: std.h:5
int32_t alt
in millimeters above WGS84 reference ellipsoid
static uint32_t get_sys_time_usec(void)
Get the time in microseconds since startup.
Definition: sys_time_arch.h:39
euler angles
#define ACCELS_BFP_OF_REAL(_ef, _ei)
Definition: pprz_algebra.h:734
uint32_t sacc
speed accuracy in cm/s
Definition: gps.h:78
Roation quaternion.
int32_t y
East.
uint32_t last_msg_time
cpu time in sec at last received GPS message
Definition: gps.h:92
uint8_t zone
UTM zone number.
float theta
in radians
int32_t r
in rad/s with INT32_RATE_FRAC
static struct NedCoor_i * stateGetSpeedNed_i(void)
Get ground speed in local NED coordinates (int).
Definition: state.h:840
#define FLOAT_VECT3_ZERO(_v)
static void stateSetSpeedNed_f(struct NedCoor_f *ned_speed)
Set ground speed in local NED coordinates (float).
Definition: state.h:792
#define TRUE
Definition: std.h:4
void float_rmat_comp(struct FloatRMat *m_a2c, struct FloatRMat *m_a2b, struct FloatRMat *m_b2c)
Composition (multiplication) of two rotation matrices.
unsigned long long uint64_t
Definition: types.h:20
int32_t hmsl
height above mean sea level in mm
Definition: gps.h:71
void float_rmat_transp_vmult(struct FloatVect3 *vb, struct FloatRMat *m_b2a, struct FloatVect3 *va)
rotate 3D vector by transposed rotation matrix.
vector in North East Down coordinates Units: meters
uint8_t mode
0-not tracking, 1 - poor performance, 2- OK
uint32_t tow
GPS time of week in ms.
Definition: gps.h:84
void float_rmat_of_quat(struct FloatRMat *rm, struct FloatQuat *q)
static void stateSetPositionLla_i(struct LlaCoor_i *lla_pos)
Set position from LLA coordinates (int).
Definition: state.h:530
struct FloatVect3 accel
Acceleration in the imu frame, m/s.
float pos_u[3]
The current GPS position uncertainty in the North East Down (NED) coordinate frame, given in meters.
static void stateSetLocalOrigin_i(struct LtpDef_i *ltp_def)
Set the local (flat earth) coordinate frame origin (int).
Definition: state.h:440
void ins_vectornav_yaw_pitch_roll_to_attitude(struct FloatEulers *vn_attitude)
Convert yaw, pitch, and roll data from VectorNav to correct attitude yaw(0), pitch(1), roll(2) -> phi, theta, psi [deg] -> rad.
int32_t x
North.
unsigned long uint32_t
Definition: types.h:18
struct EcefCoor_i ecef_pos
position in ECEF in cm
Definition: gps.h:68
PRINT_CONFIG_MSG("USE_INS_NAV_INIT defaulting to TRUE")
struct LtpDef_i ltp_def
Definition: ins_vectornav.h:72
struct Int32Rates gyro_i
struct LlaCoor_i lla
Reference point in lla.
#define DefaultPeriodic
Set default periodic telemetry.
Definition: telemetry.h:66
int32_t lon
in degrees*1e7
struct LlaCoor_f lla_pos
Definition: ins_vectornav.h:80
float baro_z
z-position calculated from baro in meters (z-down)
Definition: ins_vectornav.h:85
float vel_u
NED velocity uncertainty [m/s].
void ins_vectornav_set_pacc(void)
Find maximum uncertainty (NED) position accuracy in cm.
void ins_vectornav_read_message(void)
Read received data.
uint8_t zone
UTM zone number.
volatile uint32_t nb_sec_rem
remainder of seconds since startup in CPU_TICKS
Definition: sys_time.h:70
signed long int32_t
Definition: types.h:19
static const struct usb_device_descriptor dev
Definition: usb_ser_hw.c:69
bool_t ltp_initialized
Definition: ins_vectornav.h:73
float alt
in meters above WGS84 reference ellipsoid
void ltp_def_from_lla_f(struct LtpDef_f *def, struct LlaCoor_f *lla)
uint16_t framing_error
Definition: vn200_serial.h:65
uint32_t last_3dfix_time
cpu time in sec at last valid 3D fix
Definition: gps.h:90
int32_t alt
in millimeters above WGS84 reference ellipsoid
struct InsVectornav ins_vn
Definition: ins_vectornav.c:31
unsigned char uint8_t
Definition: types.h:14
int32_t course
GPS course over ground in rad*1e7, [0, 2*Pi]*1e7 (CW/north)
Definition: gps.h:76
struct Int32Vect3 accel_i
struct NedCoor_i ltp_speed_i
Definition: ins_vectornav.h:77
struct OrientationReps body_to_imu
body_to_imu rotation
volatile uint32_t nb_sec
full seconds since startup
Definition: sys_time.h:69
uint8_t msg_buf[VN_BUFFER_SIZE]
Definition: vn200_serial.h:59
#define LLA_BFP_OF_REAL(_o, _i)
uint16_t ins_status
see page 122 of VN-200 datasheet
int32_t p
in rad/s with INT32_RATE_FRAC
float lon
in radians
struct NedCoor_i ltp_pos_i
Definition: ins_vectornav.h:76
rotation matrix
uint32_t last_msg_ticks
cpu time ticks at last received GPS message
Definition: gps.h:91
#define INS_VN_BODY_TO_IMU_PHI
Definition: ins_vectornav.h:64
uint8_t num_sv
number of sat in fix
Definition: gps.h:81
int32_t x
in centimeters
uint16_t gspeed
norm of 2d ground speed in cm/s
Definition: gps.h:74
void ecef_of_lla_i(struct EcefCoor_i *out, struct LlaCoor_i *in)
struct EcefCoor_i ecef_vel
speed ECEF in cm/s
Definition: gps.h:72
float lat
in radians
struct LlaCoor_i lla_pos
position in LLA (lat,lon: deg*1e7; alt: mm over ellipsoid)
Definition: gps.h:69
void float_rmat_ratemult(struct FloatRates *rb, struct FloatRMat *m_a2b, struct FloatRates *ra)
rotate anglular rates by rotation matrix.
static struct NedCoor_i * stateGetPositionNed_i(void)
Get position in local NED coordinates (int).
Definition: state.h:648
int32_t lat
in degrees*1e7
static void stateSetBodyRates_f(struct FloatRates *body_rate)
Set vehicle body angular rate (float).
Definition: state.h:1152
uint8_t fix
status of fix
Definition: gps.h:82
struct FloatVect3 vel_body
The estimated velocity in the imu frame, given in m/s.
enum VNMsgStatus status
Definition: vn200_serial.h:60
void ins_vectornav_event(void)
Event handling for Vectornav.
static void stateSetAccelNed_f(struct NedCoor_f *ned_accel)
Set acceleration in NED coordinates (float).
Definition: state.h:973
int32_t q
in rad/s with INT32_RATE_FRAC
struct NedCoor_f vel_ned
The estimated velocity in the North East Down (NED) frame, given in m/s.
uint32_t vn_time
VN time stamp.
Definition: ins_vectornav.h:93
struct GpsState gps
global GPS state
Definition: gps.c:41
angular rates
void ltp_def_from_ecef_i(struct LtpDef_i *def, struct EcefCoor_i *ecef)
int8_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint8_t _id, telemetry_cb _cb)
Register a telemetry callback function.
Definition: telemetry.c:46
void utm_of_lla_f(struct UtmCoor_f *utm, struct LlaCoor_f *lla)
float timestamp
System time [s].
Definition: ins_vectornav.h:97
static struct NedCoor_i * stateGetAccelNed_i(void)
Get acceleration in NED coordinates (int).
Definition: state.h:991
float x
in meters
void ins_vectornav_init(void)
Initialize Vectornav struct.
void ins_vectornav_check_status(void)
Check INS status.
static void orientationSetEulers_f(struct OrientationReps *orientation, struct FloatEulers *eulers)
Set vehicle body attitude from euler angles (float).