36 #include "novatel_oem7_msgs/HEADING2.h" 37 #include "novatel_oem7_msgs/BESTPOS.h" 38 #include "novatel_oem7_msgs/BESTVEL.h" 39 #include "novatel_oem7_msgs/BESTUTM.h" 40 #include "novatel_oem7_msgs/INSPVA.h" 41 #include "novatel_oem7_msgs/INSPVAX.h" 42 #include "novatel_oem7_msgs/INSCONFIG.h" 43 #include "novatel_oem7_msgs/INSSTDEV.h" 44 #include "novatel_oem7_msgs/CORRIMU.h" 45 #include "novatel_oem7_msgs/RXSTATUS.h" 46 #include "novatel_oem7_msgs/TIME.h" 50 #define arr_size(_arr_) (sizeof(_arr_) / sizeof(_arr_[0])) 61 static uint32_t sequence_number = 0;
63 return ++sequence_number;
71 const Oem7RawMessageIf::ConstPtr& msg,
72 const std::string& name,
73 novatel_oem7_msgs::Oem7Header::Type& oem7_hdr
77 oem7_hdr.message_name = name;
85 const Oem7RawMessageIf::ConstPtr& msg,
86 const std::string& name,
87 novatel_oem7_msgs::Oem7Header::Type& oem7_hdr
91 oem7_hdr.message_name = name;
98 MakeROSMessage<novatel_oem7_msgs::HEADING2>(
99 const Oem7RawMessageIf::ConstPtr& msg,
105 heading2.reset(
new novatel_oem7_msgs::HEADING2);
107 heading2->sol_status.status = mem->sol_status;
108 heading2->pos_type.type = mem->pos_type;
109 heading2->length = mem->length;
110 heading2->heading = mem->heading;
111 heading2->pitch = mem->pitch;
112 heading2->reserved = mem->reserved;
113 heading2->heading_stdev = mem->heading_stdev;
114 heading2->pitch_stdev = mem->pitch_stdev;
115 heading2->rover_stn_id.assign( mem->rover_stn_id,
arr_size(mem->rover_stn_id));
116 heading2->master_stn_id.assign(mem->master_stn_id,
arr_size(mem->rover_stn_id));
117 heading2->num_sv_tracked = mem->num_sv_tracked;
118 heading2->num_sv_in_sol = mem->num_sv_in_sol;
119 heading2->num_sv_obs = mem->num_sv_obs;
120 heading2->num_sv_multi = mem->num_sv_multi;
121 heading2->sol_source.source = mem->sol_source;
122 heading2->ext_sol_status.status = mem->ext_sol_status;
123 heading2->galileo_beidou_sig_mask = mem->galileo_beidou_sig_mask;
124 heading2->gps_glonass_sig_mask = mem->gps_glonass_sig_mask;
126 static const std::string name =
"HEADING2";
132 MakeROSMessage<novatel_oem7_msgs::BESTPOS>(
133 const Oem7RawMessageIf::ConstPtr& msg,
139 bestpos.reset(
new novatel_oem7_msgs::BESTPOS);
141 bestpos->sol_status.status = bp->sol_stat;
142 bestpos->pos_type.type = bp->pos_type;
143 bestpos->lat = bp->lat;
144 bestpos->lon = bp->lon;
145 bestpos->hgt = bp->hgt;
146 bestpos->undulation = bp->undulation;
147 bestpos->datum_id = bp->datum_id;
148 bestpos->lat_stdev = bp->lat_stdev;
149 bestpos->lon_stdev = bp->lon_stdev;
150 bestpos->hgt_stdev = bp->hgt_stdev;
151 bestpos->stn_id.assign( bp->stn_id,
arr_size(bp->stn_id));
152 bestpos->diff_age = bp->diff_age;
153 bestpos->sol_age = bp->sol_age;
154 bestpos->num_svs = bp->num_svs;
155 bestpos->num_sol_svs = bp->num_sol_svs;
156 bestpos->num_sol_l1_svs = bp->num_sol_l1_svs;
157 bestpos->num_sol_multi_svs = bp->num_sol_multi_svs;
158 bestpos->reserved = bp->reserved;
159 bestpos->ext_sol_stat.status = bp->ext_sol_stat;
160 bestpos->galileo_beidou_sig_mask= bp->galileo_beidou_sig_mask;
161 bestpos->gps_glonass_sig_mask = bp->gps_glonass_sig_mask;
163 static const std::string name =
"BESTPOS";
169 MakeROSMessage<novatel_oem7_msgs::BESTVEL>(
170 const Oem7RawMessageIf::ConstPtr& msg,
176 bestvel.reset(
new novatel_oem7_msgs::BESTVEL);
178 bestvel->sol_status.status = bv->sol_stat;
179 bestvel->vel_type.type = bv->vel_type;
180 bestvel->latency = bv->latency;
181 bestvel->diff_age = bv->diff_age;
182 bestvel->hor_speed = bv->hor_speed;
183 bestvel->trk_gnd = bv->track_gnd;
184 bestvel->ver_speed = bv->ver_speed;
185 bestvel->reserved = bv->reserved;
187 static const std::string name =
"BESTVEL";
193 MakeROSMessage<novatel_oem7_msgs::BESTUTM>(
194 const Oem7RawMessageIf::ConstPtr& msg,
200 bestutm.reset(
new novatel_oem7_msgs::BESTUTM);
202 bestutm->pos_type.type = mem->pos_type;;
203 bestutm->lon_zone_number = mem->lon_zone_number;
204 bestutm->lat_zone_letter = mem->lat_zone_letter;
205 bestutm->northing = mem->northing;
206 bestutm->easting = mem->easting;
207 bestutm->height = mem->height;
208 bestutm->undulation = mem->undulation;
209 bestutm->datum_id = mem->datum_id;
210 bestutm->northing_stddev = mem->northing_stddev;
211 bestutm->easting_stddev = mem->easting_stddev;
212 bestutm->height_stddev = mem->height_stddev;
213 bestutm->stn_id.assign( mem->stn_id,
arr_size(mem->stn_id));
214 bestutm->diff_age = mem->diff_age;
215 bestutm->sol_age = mem->sol_age;
216 bestutm->num_svs = mem->num_svs;
217 bestutm->num_sol_svs = mem->num_sol_svs;
218 bestutm->num_sol_ggl1_svs = mem->num_sol_ggl1_svs;
219 bestutm->num_sol_multi_svs = mem->num_sol_multi_svs;
220 bestutm->reserved = mem->reserved;
221 bestutm->ext_sol_stat.status = mem->ext_sol_stat;
222 bestutm->galileo_beidou_sig_mask= mem->galileo_beidou_sig_mask;
223 bestutm->gps_glonass_sig_mask = mem->gps_glonass_sig_mask;
225 static const std::string name =
"BESTUTM";
231 MakeROSMessage<novatel_oem7_msgs::INSPVA>(
232 const Oem7RawMessageIf::ConstPtr& msg,
238 pva.reset(
new novatel_oem7_msgs::INSPVA);
240 pva->latitude = pvamem->latitude;
241 pva->longitude = pvamem->longitude;
242 pva->height = pvamem->height;
243 pva->north_velocity = pvamem->north_velocity;
244 pva->east_velocity = pvamem->east_velocity;
245 pva->up_velocity = pvamem->up_velocity;
246 pva->roll = pvamem->roll;
247 pva->pitch = pvamem->pitch;
248 pva->azimuth = pvamem->azimuth;
249 pva->status.status = pvamem->status;
251 static const std::string name =
"INSPVA";
258 MakeROSMessage<novatel_oem7_msgs::INSCONFIG>(
259 const Oem7RawMessageIf::ConstPtr& msg,
264 const INSCONFIG_FixedMem* insconfigmem =
266 insconfig.reset(
new novatel_oem7_msgs::INSCONFIG);
268 insconfig->imu_type = insconfigmem->imu_type;
269 insconfig->mapping = insconfigmem->mapping;
270 insconfig->initial_alignment_velocity = insconfigmem->initial_alignment_velocity;
271 insconfig->heave_window = insconfigmem->heave_window;
272 insconfig->profile = insconfigmem->profile;
275 insconfigmem->enabled_updates,
276 insconfigmem->enabled_updates +
arr_size(insconfigmem->enabled_updates),
277 insconfig->enabled_updates.begin());
279 insconfig->alignment_mode.mode = insconfigmem->alignment_mode;
280 insconfig->relative_ins_output_frame.frame = insconfigmem->relative_ins_output_frame;
281 insconfig->relative_ins_output_direction = insconfigmem->relative_ins_output_direction;
284 insconfigmem->ins_receiver_status,
285 insconfigmem->ins_receiver_status +
arr_size(insconfigmem->ins_receiver_status),
286 insconfig->ins_receiver_status.status.begin());
288 insconfig->ins_seed_enabled = insconfigmem->ins_seed_enabled;
289 insconfig->ins_seed_validation = insconfigmem->ins_seed_validation;
290 insconfig->reserved_1 = insconfigmem->reserved_1;
291 insconfig->reserved_2 = insconfigmem->reserved_2;
292 insconfig->reserved_3 = insconfigmem->reserved_3;
293 insconfig->reserved_4 = insconfigmem->reserved_4;
294 insconfig->reserved_5 = insconfigmem->reserved_5;
295 insconfig->reserved_6 = insconfigmem->reserved_6;
296 insconfig->reserved_7 = insconfigmem->reserved_7;
304 novatel_oem7_msgs::Translation& tr = insconfig->translations[idx];
306 tr.translation.type = trmem->translation;
307 tr.frame.frame = trmem->frame;
308 tr.x_offset = trmem->x_offset;
309 tr.y_offset = trmem->y_offset;
310 tr.z_offset = trmem->z_offset;
311 tr.x_uncertainty = trmem->x_uncertainty;
312 tr.y_uncertainty = trmem->y_uncertainty;
313 tr.z_uncertainty = trmem->z_uncertainty;
314 tr.translation_source.status = trmem->translation_source;
323 novatel_oem7_msgs::Rotation& rt = insconfig->rotations[idx];
324 rt.rotation.offset = rtmem->rotation;
325 rt.frame.frame = rtmem->frame;
326 rt.x_rotation = rtmem->x_rotation;
327 rt.y_rotation = rtmem->y_rotation;
328 rt.z_rotation = rtmem->z_rotation;
329 rt.x_rotation_stdev = rtmem->x_rotation_stdev;
330 rt.y_rotation_stdev = rtmem->y_rotation_stdev;
331 rt.z_rotation_stdev = rtmem->z_rotation_stdev;
332 rt.rotation_source.status = rtmem->rotation_source;
335 static const std::string name =
"INSCONFIG";
342 MakeROSMessage<novatel_oem7_msgs::INSPVAX>(
343 const Oem7RawMessageIf::ConstPtr& msg,
349 inspvax.reset(
new novatel_oem7_msgs::INSPVAX);
351 inspvax->ins_status.status = mem->ins_status;
352 inspvax->pos_type.type = mem->pos_type;
353 inspvax->latitude = mem->latitude;
354 inspvax->longitude = mem->longitude;
355 inspvax->height = mem->height;
356 inspvax->undulation = mem->undulation;
357 inspvax->north_velocity = mem->north_velocity;
358 inspvax->east_velocity = mem->east_velocity;
359 inspvax->up_velocity = mem->up_velocity;
360 inspvax->roll = mem->roll;
361 inspvax->pitch = mem->pitch;
362 inspvax->azimuth = mem->azimuth;
363 inspvax->latitude_stdev = mem->latitude_stdev;
364 inspvax->longitude_stdev = mem->longitude_stdev;
365 inspvax->height_stdev = mem->height_stdev;
366 inspvax->north_velocity_stdev = mem->north_velocity_stdev;
367 inspvax->east_velocity_stdev = mem->east_velocity_stdev;
368 inspvax->up_velocity_stdev = mem->up_velocity_stdev;
369 inspvax->roll_stdev = mem->roll_stdev;
370 inspvax->pitch_stdev = mem->pitch_stdev;
371 inspvax->azimuth_stdev = mem->azimuth_stdev;
372 inspvax->ext_sol_status.status = mem->extended_status;
374 static const std::string name =
"INSPVAX";
382 MakeROSMessage<novatel_oem7_msgs::INSSTDEV>(
383 const Oem7RawMessageIf::ConstPtr& msg,
389 insstdev.reset(
new novatel_oem7_msgs::INSSTDEV);
391 insstdev->latitude_stdev = raw->latitude_stdev;
392 insstdev->longitude_stdev = raw->longitude_stdev;
393 insstdev->height_stdev = raw->height_stdev;
394 insstdev->north_velocity_stdev = raw->north_velocity_stdev;
395 insstdev->east_velocity_stdev = raw->east_velocity_stdev;
396 insstdev->up_velocity_stdev = raw->up_velocity_stdev;
397 insstdev->roll_stdev = raw->roll_stdev;
398 insstdev->pitch_stdev = raw->pitch_stdev;
399 insstdev->azimuth_stdev = raw->azimuth_stdev;
400 insstdev->ext_sol_status.status = raw->ext_sol_status;
401 insstdev->time_since_last_update = raw->time_since_last_update;
402 insstdev->reserved1 = raw->reserved1;
403 insstdev->reserved2 = raw->reserved2;
404 insstdev->reserved3 = raw->reserved3;
406 static const std::string name =
"INSSTDEV";
412 MakeROSMessage<novatel_oem7_msgs::CORRIMU>(
413 const Oem7RawMessageIf::ConstPtr& msg,
416 corrimu.reset(
new novatel_oem7_msgs::CORRIMU);
421 corrimu->imu_data_count = raw->imu_data_count;
422 corrimu->pitch_rate = raw->pitch_rate;
423 corrimu->roll_rate = raw->roll_rate;
424 corrimu->yaw_rate = raw->yaw_rate;
425 corrimu->lateral_acc = raw->lateral_acc;
426 corrimu->longitudinal_acc = raw->longitudinal_acc;
427 corrimu->vertical_acc = raw->vertical_acc;
431 const IMURATECORRIMUSMem* raw =
433 corrimu->imu_data_count = 0;
434 corrimu->pitch_rate = raw->pitch_rate;
435 corrimu->roll_rate = raw->roll_rate;
436 corrimu->yaw_rate = raw->yaw_rate;
437 corrimu->lateral_acc = raw->lateral_acc;
438 corrimu->longitudinal_acc = raw->longitudinal_acc;
439 corrimu->vertical_acc = raw->vertical_acc;
446 static const std::string name =
"CORRIMU";
452 MakeROSMessage<novatel_oem7_msgs::TIME>(
453 const Oem7RawMessageIf::ConstPtr& msg,
459 time.reset(
new novatel_oem7_msgs::TIME);
461 time->clock_status = mem->clock_status;
462 time->offset = mem->offset;
463 time->offset_std = mem->offset_std;
464 time->utc_offset = mem->utc_offset;
465 time->utc_year = mem->utc_year;
466 time->utc_month = mem->utc_month;
467 time->utc_day = mem->utc_day;
468 time->utc_hour = mem->utc_hour;
469 time->utc_min = mem->utc_min;
470 time->utc_msec = mem->utc_msec;
471 time->utc_status = mem->utc_status;
473 static const std::string name =
"TIME";
479 MakeROSMessage<novatel_oem7_msgs::RXSTATUS>(
480 const Oem7RawMessageIf::ConstPtr& msg,
486 rxstatus.reset(
new novatel_oem7_msgs::RXSTATUS);
488 rxstatus->error = mem->error;
489 rxstatus->num_status_codes = mem->num_status_codes;
490 rxstatus->rxstat = mem->rxstat;
491 rxstatus->rxstat_pri_mask = mem->rxstat_pri_mask;
492 rxstatus->rxstat_set_mask = mem->rxstat_set_mask;
493 rxstatus->rxstat_clr_mask = mem->rxstat_clr_mask;
494 rxstatus->aux1_stat = mem->aux1_stat;
495 rxstatus->aux1_stat_pri = mem->aux1_stat_pri;
496 rxstatus->aux1_stat_set = mem->aux1_stat_set;
497 rxstatus->aux1_stat_clr = mem->aux1_stat_clr;
498 rxstatus->aux2_stat = mem->aux2_stat;
499 rxstatus->aux2_stat_pri = mem->aux2_stat_pri;
500 rxstatus->aux2_stat_set = mem->aux2_stat_set;
501 rxstatus->aux2_stat_clr = mem->aux2_stat_clr;
502 rxstatus->aux3_stat = mem->aux3_stat;
503 rxstatus->aux3_stat_pri = mem->aux3_stat_pri;
504 rxstatus->aux3_stat_set = mem->aux3_stat_set;
505 rxstatus->aux3_stat_clr = mem->aux3_stat_clr;
506 rxstatus->aux4_stat = mem->aux4_stat;
507 rxstatus->aux4_stat_pri = mem->aux4_stat_pri;
508 rxstatus->aux4_stat_set = mem->aux4_stat_set;
509 rxstatus->aux4_stat_clr = mem->aux4_stat_clr;
512 static const std::string name =
"RXSTATUS";
565 const Oem7RawMessageIf::ConstPtr& msg,
566 uint32_t system_to_use,
573 const PSRDOP2_FixedMem* mem =
reinterpret_cast<const PSRDOP2_FixedMem*
>(msg->getMessageData(
OEM7_BINARY_MSG_HDR_LEN));
587 if(sys->system == system_to_use)
const int BESTUTM_OEM7_MSGID
const int TIME_OEM7_MSGID
const int RXSTATUS_OEM7_MSGID
const std::size_t OEM7_BINARY_MSG_SHORT_HDR_LEN
void SetOem7Header(const Oem7RawMessageIf::ConstPtr &msg, const std::string &name, novatel_oem7_msgs::Oem7Header::Type &oem7_hdr)
const int BESTPOS_OEM7_MSGID
const int BESTVEL_OEM7_MSGID
const int INSCONFIG_OEM7_MSGID
const PSRDOP2_SystemMem * Get_PSRDOP2_System(const PSRDOP2_FixedMem *psrdop2, size_t idx)
size_t Get_INSCONFIG_NumTranslations(const INSCONFIG_FixedMem *insconfig)
const int HEADING2_OEM7_MSGID
const int INSPVAX_OEM7_MSGID
const INSCONFIG_TranslationMem * Get_INSCONFIG_Translation(const INSCONFIG_FixedMem *insconfig, size_t idx)
const std::size_t OEM7_BINARY_MSG_HDR_LEN
size_t Get_PSRDOP2_NumSystems(const PSRDOP2_FixedMem *psrdop2)
const int INSPVAS_OEM7_MSGID
void SetOem7ShortHeader(const Oem7RawMessageIf::ConstPtr &msg, const std::string &name, novatel_oem7_msgs::Oem7Header::Type &oem7_hdr)
void getOem7ShortHeader(const Oem7RawMessageIf::ConstPtr &raw_msg, novatel_oem7_msgs::Oem7Header::Type &hdr)
size_t Get_INSCONFIG_NumRotations(const INSCONFIG_FixedMem *insconfig)
const int IMURATECORRIMUS_OEM7_MSGID
void getOem7Header(const Oem7RawMessageIf::ConstPtr &raw_msg, novatel_oem7_msgs::Oem7Header::Type &hdr)
void MakeROSMessage(const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< T > &rosmsg)
const int INSSTDEV_OEM7_MSGID
const int CORRIMUS_OEM7_MSGID
void GetDOPFromPSRDOP2(const Oem7RawMessageIf::ConstPtr &msg, uint32_t system_to_use, double &gdop, double &pdop, double &hdop, double &vdop, double &tdop)
const INSCONFIG_RotationMem * Get_INSCONFIG_Rotation(const INSCONFIG_FixedMem *insconfig, size_t idx)
uint32_t GetNextMsgSequenceNumber()