ellipse_msg.cpp
Go to the documentation of this file.
1 #include "ellipse_msg.h"
2 
3 void read_ecom_log_status(sbg_driver::SbgStatus &msg, const SbgBinaryLogData *pLogData){
4  msg.header.stamp = ros::Time::now();
5  msg.time_stamp = pLogData->statusData.timeStamp;
6 
7  msg.status_general.main_power = (pLogData->statusData.generalStatus & (1 << 0)) >> 0;
8  msg.status_general.imu_power = (pLogData->statusData.generalStatus & (1 << 1)) >> 1;
9  msg.status_general.gps_power = (pLogData->statusData.generalStatus & (1 << 2)) >> 2;
10  msg.status_general.settings = (pLogData->statusData.generalStatus & (1 << 3)) >> 3;
11  msg.status_general.temperature = (pLogData->statusData.generalStatus & (1 << 4)) >> 4;
12 
13  msg.status_com.port_a = (pLogData->statusData.comStatus & (1 << 0)) >> 0;
14  msg.status_com.port_b = (pLogData->statusData.comStatus & (1 << 1)) >> 1;
15  msg.status_com.port_c = (pLogData->statusData.comStatus & (1 << 2)) >> 2;
16  msg.status_com.port_d = (pLogData->statusData.comStatus & (1 << 3)) >> 3;
17  msg.status_com.port_e = (pLogData->statusData.comStatus & (1 << 4)) >> 4;
18  msg.status_com.port_a_rx = (pLogData->statusData.comStatus & (1 << 5)) >> 5;
19  msg.status_com.port_a_tx = (pLogData->statusData.comStatus & (1 << 6)) >> 6;
20  msg.status_com.port_b_rx = (pLogData->statusData.comStatus & (1 << 7)) >> 7;
21  msg.status_com.port_b_tx = (pLogData->statusData.comStatus & (1 << 8)) >> 8;
22  msg.status_com.port_c_rx = (pLogData->statusData.comStatus & (1 << 9)) >> 9;
23  msg.status_com.port_c_tx = (pLogData->statusData.comStatus & (1 << 10)) >> 10;
24  msg.status_com.port_d_rx = (pLogData->statusData.comStatus & (1 << 11)) >> 11;
25  msg.status_com.port_d_tx = (pLogData->statusData.comStatus & (1 << 12)) >> 12;
26  msg.status_com.port_e_rx = (pLogData->statusData.comStatus & (1 << 13)) >> 13;
27  msg.status_com.port_e_tx = (pLogData->statusData.comStatus & (1 << 14)) >> 14;
28  msg.status_com.can_rx = (pLogData->statusData.comStatus & (1 << 25)) >> 25;
29  msg.status_com.can_tx = (pLogData->statusData.comStatus & (1 << 26)) >> 26;
30  msg.status_com.can_status = (pLogData->statusData.comStatus & (0b111 << 27)) >> 27;
31 
32  msg.status_aiding.gps1_pos_recv = (pLogData->statusData.aidingStatus & (1 << 0)) >> 0;
33  msg.status_aiding.gps1_vel_recv = (pLogData->statusData.aidingStatus & (1 << 1)) >> 1;
34  msg.status_aiding.gps1_hdt_recv = (pLogData->statusData.aidingStatus & (1 << 2)) >> 2;
35  msg.status_aiding.gps1_utc_recv = (pLogData->statusData.aidingStatus & (1 << 3)) >> 3;
36  msg.status_aiding.mag_recv = (pLogData->statusData.aidingStatus & (1 << 8)) >> 8;
37  msg.status_aiding.odo_recv = (pLogData->statusData.aidingStatus & (1 << 9)) >> 9;
38  msg.status_aiding.dvl_recv = (pLogData->statusData.aidingStatus & (1 << 10)) >> 10;
39 }
40 
41 void read_ecom_log_utc_time(sbg_driver::SbgUtcTime &msg, const SbgBinaryLogData *pLogData){
42  msg.header.stamp = ros::Time::now();
43  msg.time_stamp = pLogData->utcData.timeStamp;
44 
45  msg.clock_status.clock_stable = (pLogData->utcData.status & (1 << 0)) >> 0;
46  msg.clock_status.clock_status = (pLogData->utcData.status & (0b1111 << 1)) >> 1;
47  msg.clock_status.clock_utc_sync = (pLogData->utcData.status & (1 << 5)) >> 5;
48  msg.clock_status.clock_utc_status = (pLogData->utcData.status & (0b1111 << 6)) >> 6;
49  msg.year = pLogData->utcData.year;
50  msg.month = pLogData->utcData.month;
51  msg.day = pLogData->utcData.day;
52  msg.hour = pLogData->utcData.hour;
53  msg.min = pLogData->utcData.minute;
54  msg.sec = pLogData->utcData.second;
55  msg.nanosec = pLogData->utcData.nanoSecond;
56  msg.gps_tow = pLogData->utcData.gpsTimeOfWeek;
57 }
58 
59 void read_ecom_log_imu_data(sbg_driver::SbgImuData &msg, const SbgBinaryLogData *pLogData){
60  msg.header.stamp = ros::Time::now();
61  msg.time_stamp = pLogData->imuData.timeStamp;
62 
63  msg.imu_status.imu_com = (pLogData->imuData.status & (1 << 0)) >> 0;
64  msg.imu_status.imu_status = (pLogData->imuData.status & (1 << 1)) >> 1;
65  msg.imu_status.imu_accel_x = (pLogData->imuData.status & (1 << 2)) >> 2;
66  msg.imu_status.imu_accel_y = (pLogData->imuData.status & (1 << 3)) >> 3;
67  msg.imu_status.imu_accel_z = (pLogData->imuData.status & (1 << 4)) >> 4;
68  msg.imu_status.imu_gyro_x = (pLogData->imuData.status & (1 << 5)) >> 5;
69  msg.imu_status.imu_gyro_y = (pLogData->imuData.status & (1 << 6)) >> 6;
70  msg.imu_status.imu_gyro_z = (pLogData->imuData.status & (1 << 7)) >> 7;
71  msg.imu_status.imu_accels_in_range = (pLogData->imuData.status & (1 << 8)) >> 8;
72  msg.imu_status.imu_gyros_in_range = (pLogData->imuData.status & (1 << 9)) >> 9;
73 
74  msg.accel.x = pLogData->imuData.accelerometers[0];
75  msg.accel.y = pLogData->imuData.accelerometers[1];
76  msg.accel.z = pLogData->imuData.accelerometers[2];
77  msg.gyro.x = pLogData->imuData.gyroscopes[0];
78  msg.gyro.y = pLogData->imuData.gyroscopes[1];
79  msg.gyro.z = pLogData->imuData.gyroscopes[2];
80  msg.temp = pLogData->imuData.temperature;
81  msg.delta_vel.x = pLogData->imuData.deltaVelocity[0];
82  msg.delta_vel.y = pLogData->imuData.deltaVelocity[1];
83  msg.delta_vel.z = pLogData->imuData.deltaVelocity[2];
84  msg.delta_angle.x = pLogData->imuData.deltaAngle[0];
85  msg.delta_angle.y = pLogData->imuData.deltaAngle[1];
86  msg.delta_angle.z = pLogData->imuData.deltaAngle[2];
87 }
88 
89 void read_ekf_solution_status(sbg_driver::SbgEkfStatus &msg, const uint32 &val){
90  msg.solution_mode = val & (0b1111);
91  msg.attitude_valid = (val & (1 << 4)) >> 4;
92  msg.heading_valid = (val & (1 << 5)) >> 5;
93  msg.velocity_valid = (val & (1 << 6)) >> 6;
94  msg.position_valid = (val & (1 << 7)) >> 7;
95  msg.vert_ref_used = (val & (1 << 8)) >> 8;
96  msg.mag_ref_used = (val & (1 << 9)) >> 9;
97  msg.gps1_vel_used = (val & (1 << 10)) >> 10;
98  msg.gps1_pos_used = (val & (1 << 11)) >> 11;
99  msg.gps1_course_used = (val & (1 << 12)) >> 12;
100  msg.gps1_hdt_used = (val & (1 << 13)) >> 13;
101  msg.gps2_vel_used = (val & (1 << 14)) >> 14;
102  msg.gps2_pos_used = (val & (1 << 15)) >> 15;
103  msg.gps2_course_used = (val & (1 << 16)) >> 16;
104  msg.gps2_hdt_used = (val & (1 << 17)) >> 17;
105  msg.odo_used = (val & (1 << 18)) >> 18;
106 }
107 
108 void read_ecom_log_ekf_euler(sbg_driver::SbgEkfEuler &msg, const SbgBinaryLogData *pLogData){
109  msg.header.stamp = ros::Time::now();
110  msg.time_stamp = pLogData->ekfEulerData.timeStamp;
111  msg.angle.x = pLogData->ekfEulerData.euler[0];
112  msg.angle.y = pLogData->ekfEulerData.euler[1];
113  msg.angle.z = pLogData->ekfEulerData.euler[2];
114  msg.accuracy.x = pLogData->ekfEulerData.eulerStdDev[0];
115  msg.accuracy.y = pLogData->ekfEulerData.eulerStdDev[1];
116  msg.accuracy.z = pLogData->ekfEulerData.eulerStdDev[2];
117  read_ekf_solution_status(msg.status, pLogData->ekfEulerData.status);
118 }
119 
120 void read_ecom_log_ekf_quat(sbg_driver::SbgEkfQuat &msg, const SbgBinaryLogData *pLogData){
121  msg.header.stamp = ros::Time::now();
122  msg.header.stamp = ros::Time::now();
123  msg.time_stamp = pLogData->ekfQuatData.timeStamp;
124  msg.quaternion.x = pLogData->ekfQuatData.quaternion[1];
125  msg.quaternion.y = pLogData->ekfQuatData.quaternion[2];
126  msg.quaternion.z = pLogData->ekfQuatData.quaternion[3];
127  msg.quaternion.w = pLogData->ekfQuatData.quaternion[0];
128  msg.accuracy.x = pLogData->ekfQuatData.eulerStdDev[0];
129  msg.accuracy.y = pLogData->ekfQuatData.eulerStdDev[1];
130  msg.accuracy.z = pLogData->ekfQuatData.eulerStdDev[2];
131  read_ekf_solution_status(msg.status, pLogData->ekfQuatData.status);
132 }
133 
134 void read_ecom_log_ekf_nav(sbg_driver::SbgEkfNav &msg, const SbgBinaryLogData *pLogData){
135  msg.header.stamp = ros::Time::now();
136 
137  msg.time_stamp = pLogData->ekfNavData.timeStamp;
138  msg.velocity.x = pLogData->ekfNavData.velocity[0];
139  msg.velocity.y = pLogData->ekfNavData.velocity[1];
140  msg.velocity.z = pLogData->ekfNavData.velocity[2];
141  msg.velocity_accuracy.x = pLogData->ekfNavData.velocityStdDev[0];
142  msg.velocity_accuracy.y = pLogData->ekfNavData.velocityStdDev[1];
143  msg.velocity_accuracy.z = pLogData->ekfNavData.velocityStdDev[2];
144  msg.position.x = pLogData->ekfNavData.position[0];
145  msg.position.y = pLogData->ekfNavData.position[1];
146  msg.position.z = pLogData->ekfNavData.position[2];
147  msg.undulation = pLogData->ekfNavData.undulation;
148 
149  read_ekf_solution_status(msg.status, pLogData->ekfNavData.status);
150 }
151 
152 void read_ecom_log_ship_motion(sbg_driver::SbgShipMotion &msg, const SbgBinaryLogData *pLogData){
153  msg.header.stamp = ros::Time::now();
154  msg.time_stamp = pLogData->shipMotionData.timeStamp;
155  msg.heave_period = pLogData->shipMotionData.mainHeavePeriod;
156  msg.ship_motion.x = pLogData->shipMotionData.shipMotion[0];
157  msg.ship_motion.y = pLogData->shipMotionData.shipMotion[1];
158  msg.ship_motion.z = pLogData->shipMotionData.shipMotion[2];
159  msg.acceleration.x = pLogData->shipMotionData.shipAccel[0];
160  msg.acceleration.y = pLogData->shipMotionData.shipAccel[1];
161  msg.acceleration.z = pLogData->shipMotionData.shipAccel[2];
162  msg.velocity.x = pLogData->shipMotionData.shipVel[0];
163  msg.velocity.y = pLogData->shipMotionData.shipVel[1];
164  msg.velocity.z = pLogData->shipMotionData.shipVel[2];
165 
166  msg.status.heave_valid = (pLogData->shipMotionData.status & (1 << 0)) >> 0;
167  msg.status.heave_vel_aided = (pLogData->shipMotionData.status & (1 << 1)) >> 1;
168  msg.status.period_available = (pLogData->shipMotionData.status & (1 << 2)) >> 2;
169  msg.status.period_valid = (pLogData->shipMotionData.status & (1 << 3)) >> 3;
170 }
171 
172 void read_mag_status(sbg_driver::SbgMagStatus &msg, const uint16 &val){
173  msg.mag_x = (val & (1 << 0)) >> 0;
174  msg.mag_y = (val & (1 << 1)) >> 1;
175  msg.mag_z = (val & (1 << 2)) >> 2;
176  msg.accel_x = (val & (1 << 3)) >> 3;
177  msg.accel_y = (val & (1 << 4)) >> 4;
178  msg.accel_z = (val & (1 << 5)) >> 5;
179  msg.mags_in_range = (val & (1 << 6)) >> 6;
180  msg.accels_in_range = (val & (1 << 7)) >> 7;
181  msg.calibration = (val & (1 << 8)) >> 8;
182 }
183 
184 void read_ecom_log_mag(sbg_driver::SbgMag &msg, const SbgBinaryLogData *pLogData){
185  msg.header.stamp = ros::Time::now();
186  msg.time_stamp = pLogData->magData.timeStamp;
187 
188  msg.mag.x = pLogData->magData.magnetometers[0];
189  msg.mag.y = pLogData->magData.magnetometers[1];
190  msg.mag.z = pLogData->magData.magnetometers[2];
191  msg.accel.x = pLogData->magData.accelerometers[0];
192  msg.accel.y = pLogData->magData.accelerometers[1];
193  msg.accel.z = pLogData->magData.accelerometers[2];
194 
195  read_mag_status(msg.status, pLogData->magData.status);
196 }
197 
198 void read_ecom_log_mag_calib(sbg_driver::SbgMagCalib &msg, const SbgBinaryLogData *pLogData){
199  msg.header.stamp = ros::Time::now();
200  ROS_INFO("SBG DRIVER - SbgMagCalib message not implemented");
201 }
202 
203 void read_gps_vel_status(sbg_driver::SbgGpsVelStatus &msg, const uint32 &val){
204  msg.vel_status = (val & (0b111111 << 0)) >> 0;
205  msg.vel_type = (val & (0b111111 << 6)) >> 6;
206 }
207 
208 void read_ecom_log_gps_vel(sbg_driver::SbgGpsVel &msg, const SbgBinaryLogData *pLogData){
209  msg.header.stamp = ros::Time::now();
210  msg.time_stamp = pLogData->gpsVelData.timeStamp;
211 
212  msg.gps_tow = pLogData->gpsVelData.timeOfWeek;
213  msg.vel.x = pLogData->gpsVelData.velocity[0];
214  msg.vel.y = pLogData->gpsVelData.velocity[1];
215  msg.vel.z = pLogData->gpsVelData.velocity[2];
216  msg.vel_acc.x = pLogData->gpsVelData.velocityAcc[0];
217  msg.vel_acc.y = pLogData->gpsVelData.velocityAcc[1];
218  msg.vel_acc.z = pLogData->gpsVelData.velocityAcc[2];
219  msg.course = pLogData->gpsVelData.course;
220  msg.course_acc = pLogData->gpsVelData.courseAcc;
221 
222  read_gps_vel_status(msg.status, pLogData->gpsVelData.status);
223 }
224 
225 void read_gps_pos_status(sbg_driver::SbgGpsPosStatus &msg, const uint32 &val){
226  msg.status = (val & (0b111111 << 0)) >> 6;
227  msg.type = (val & (0b111111 << 6)) >> 6;
228  msg.gps_l1_used = (val & (1 << 12)) >> 12;
229  msg.gps_l2_used = (val & (1 << 13)) >> 13;
230  msg.gps_l5_used = (val & (1 << 14)) >> 14;
231  msg.glo_l1_used = (val & (1 << 15)) >> 15;
232  msg.glo_l2_used = (val & (1 << 16)) >> 16;
233 }
234 
235 void read_ecom_log_gps_pos(sbg_driver::SbgGpsPos &msg, const SbgBinaryLogData *pLogData){
236  msg.header.stamp = ros::Time::now();
237  msg.time_stamp = pLogData->gpsPosData.timeStamp;
238 
239  msg.gps_tow = pLogData->gpsPosData.timeOfWeek;
240  msg.position.x = pLogData->gpsPosData.latitude;
241  msg.position.y = pLogData->gpsPosData.longitude;
242  msg.position.z = pLogData->gpsPosData.altitude;
243  msg.undulation = pLogData->gpsPosData.undulation;
244  msg.position_accuracy.x = pLogData->gpsPosData.latitudeAccuracy;
245  msg.position_accuracy.y = pLogData->gpsPosData.longitudeAccuracy;
246  msg.position_accuracy.z = pLogData->gpsPosData.altitudeAccuracy;
247  msg.num_sv_used = pLogData->gpsPosData.numSvUsed;
248  msg.base_station_id = pLogData->gpsPosData.baseStationId;
249  msg.diff_age = pLogData->gpsPosData.differentialAge;
250 
251  read_gps_pos_status(msg.status, pLogData->gpsPosData.status);
252 
253 }
254 
255 void read_ecom_log_gps_hdt(sbg_driver::SbgGpsHdt &msg, const SbgBinaryLogData *pLogData){
256  msg.header.stamp = ros::Time::now();
257  msg.time_stamp = pLogData->gpsHdtData.timeStamp;
258 
259  msg.status = pLogData->gpsHdtData.status & 0b111111;
260  msg.tow = pLogData->gpsHdtData.timeOfWeek;
261  msg.true_heading = pLogData->gpsHdtData.heading;
262  msg.true_heading_acc = pLogData->gpsHdtData.headingAccuracy;
263  msg.pitch = pLogData->gpsHdtData.pitch;
264  msg.pitch_acc = pLogData->gpsHdtData.pitchAccuracy;
265 }
266 
267 void read_ecom_log_gps_raw(sbg_driver::SbgGpsRaw &msg, const SbgBinaryLogData *pLogData){
268  msg.header.stamp = ros::Time::now();
269  msg.data.assign(pLogData->gpsRawData.rawBuffer, pLogData->gpsRawData.rawBuffer + pLogData->gpsRawData.bufferSize);
270 }
271 
272 void read_ecom_log_odo_vel(sbg_driver::SbgOdoVel &msg, const SbgBinaryLogData *pLogData){
273  msg.header.stamp = ros::Time::now();
274  msg.time_stamp = pLogData->odometerData.timeStamp;
275  msg.status = pLogData->odometerData.status & 1;
276  msg.vel = pLogData->odometerData.velocity;
277 }
278 
279 void read_ecom_log_event(sbg_driver::SbgEvent &msg, const SbgBinaryLogData *pLogData){
280  msg.header.stamp = ros::Time::now();
281  msg.time_stamp = pLogData->eventMarker.timeStamp;
282 
283  msg.overflow = (pLogData->eventMarker.status & (1 << 0)) >> 0;
284  msg.offset_0_valid = (pLogData->eventMarker.status & (1 << 1)) >> 1;
285  msg.offset_1_valid = (pLogData->eventMarker.status & (1 << 2)) >> 2;
286  msg.offset_2_valid = (pLogData->eventMarker.status & (1 << 3)) >> 3;
287  msg.offset_3_valid = (pLogData->eventMarker.status & (1 << 4)) >> 4;
288 
289  msg.time_offset_0 = pLogData->eventMarker.timeOffset0;
290  msg.time_offset_1 = pLogData->eventMarker.timeOffset1;
291  msg.time_offset_2 = pLogData->eventMarker.timeOffset2;
292  msg.time_offset_3 = pLogData->eventMarker.timeOffset3;
293 }
294 
295 void read_ecom_log_pressure(sbg_driver::SbgPressure &msg, const SbgBinaryLogData *pLogData){
296  msg.header.stamp = ros::Time::now();
297  msg.time_stamp = pLogData->pressureData.timeStamp;
298 
299  msg.valid_pressure = (pLogData->pressureData.status & (1 << 0)) >> 0;
300  msg.valid_altitude = (pLogData->pressureData.status & (1 << 1)) >> 1;
301  msg.pressure = pLogData->pressureData.pressure;
302  msg.altitude = pLogData->pressureData.height;
303 }
304 
305 void read_get_info(SbgEComHandle *comHandle){
306  SbgEComDeviceInfo pInfo;
307  SbgErrorCode errorCode = sbgEComCmdGetInfo(comHandle, &pInfo);
308  if (errorCode != SBG_NO_ERROR){ROS_WARN("SBG DRIVER - sbgEComCmdGetInfo Error : %s", sbgErrorCodeToString(errorCode));}
309 
310  ROS_INFO("SBG DRIVER - productCode = %s", pInfo.productCode);
311  ROS_INFO("SBG DRIVER - serialNumber = %u", pInfo.serialNumber);
312  ROS_INFO("SBG DRIVER - calibationRev = %u", pInfo.calibationRev);
313  ROS_INFO("SBG DRIVER - calibrationYear = %u", pInfo.calibrationYear);
314  ROS_INFO("SBG DRIVER - calibrationMonth = %u", pInfo.calibrationMonth);
315  ROS_INFO("SBG DRIVER - calibrationDay = %u", pInfo.calibrationDay);
316  ROS_INFO("SBG DRIVER - hardwareRev = %u", pInfo.hardwareRev);
317  ROS_INFO("SBG DRIVER - firmwareRev = %u", pInfo.firmwareRev);
318 }
SbgLogEkfNavData ekfNavData
void read_mag_status(sbg_driver::SbgMagStatus &msg, const uint16 &val)
SbgLogEkfEulerData ekfEulerData
SbgLogEkfQuatData ekfQuatData
unsigned int uint32
Definition: sbgTypes.h:58
void read_ecom_log_status(sbg_driver::SbgStatus &msg, const SbgBinaryLogData *pLogData)
Definition: ellipse_msg.cpp:3
void read_ecom_log_ekf_nav(sbg_driver::SbgEkfNav &msg, const SbgBinaryLogData *pLogData)
SbgLogImuData imuData
SbgLogEvent eventMarker
void read_ecom_log_gps_pos(sbg_driver::SbgGpsPos &msg, const SbgBinaryLogData *pLogData)
void read_ecom_log_ship_motion(sbg_driver::SbgShipMotion &msg, const SbgBinaryLogData *pLogData)
void read_ecom_log_pressure(sbg_driver::SbgPressure &msg, const SbgBinaryLogData *pLogData)
uint8 productCode[SBG_ECOM_INFO_PRODUCT_CODE_LENGTH]
void read_ecom_log_utc_time(sbg_driver::SbgUtcTime &msg, const SbgBinaryLogData *pLogData)
Definition: ellipse_msg.cpp:41
#define ROS_WARN(...)
void read_ecom_log_mag(sbg_driver::SbgMag &msg, const SbgBinaryLogData *pLogData)
SbgLogGpsVel gpsVelData
SbgLogOdometerData odometerData
void read_ekf_solution_status(sbg_driver::SbgEkfStatus &msg, const uint32 &val)
Definition: ellipse_msg.cpp:89
uint8 rawBuffer[SBG_ECOM_GPS_RAW_MAX_BUFFER_SIZE]
float accelerometers[3]
SBG_INLINE const char * sbgErrorCodeToString(SbgErrorCode errorCode)
Definition: sbgErrorCodes.h:71
void read_gps_vel_status(sbg_driver::SbgGpsVelStatus &msg, const uint32 &val)
#define ROS_INFO(...)
float magnetometers[3]
SbgLogGpsPos gpsPosData
void read_gps_pos_status(sbg_driver::SbgGpsPosStatus &msg, const uint32 &val)
void read_ecom_log_odo_vel(sbg_driver::SbgOdoVel &msg, const SbgBinaryLogData *pLogData)
void read_ecom_log_ekf_quat(sbg_driver::SbgEkfQuat &msg, const SbgBinaryLogData *pLogData)
void read_get_info(SbgEComHandle *comHandle)
void read_ecom_log_gps_vel(sbg_driver::SbgGpsVel &msg, const SbgBinaryLogData *pLogData)
void read_ecom_log_gps_raw(sbg_driver::SbgGpsRaw &msg, const SbgBinaryLogData *pLogData)
void read_ecom_log_imu_data(sbg_driver::SbgImuData &msg, const SbgBinaryLogData *pLogData)
Definition: ellipse_msg.cpp:59
void read_ecom_log_gps_hdt(sbg_driver::SbgGpsHdt &msg, const SbgBinaryLogData *pLogData)
SbgLogPressureData pressureData
static Time now()
SbgErrorCode sbgEComCmdGetInfo(SbgEComHandle *pHandle, SbgEComDeviceInfo *pInfo)
void read_ecom_log_event(sbg_driver::SbgEvent &msg, const SbgBinaryLogData *pLogData)
SbgLogShipMotionData shipMotionData
unsigned short uint16
Definition: sbgTypes.h:57
SbgLogStatusData statusData
SbgLogUtcData utcData
SbgLogGpsHdt gpsHdtData
enum _SbgErrorCode SbgErrorCode
void read_ecom_log_mag_calib(sbg_driver::SbgMagCalib &msg, const SbgBinaryLogData *pLogData)
void read_ecom_log_ekf_euler(sbg_driver::SbgEkfEuler &msg, const SbgBinaryLogData *pLogData)
SbgLogGpsRaw gpsRawData


sbg_driver
Author(s):
autogenerated on Sun Jan 27 2019 03:42:19