4 #include <boost/date_time/gregorian/gregorian.hpp>
5 #include <boost/date_time/posix_time/posix_time.hpp>
23 ROS_WARN(
"This timestamp source is not available. You can use ins or ros. By "
24 "default we replace your value by ins.");
34 ROS_WARN(
"This timestamp origin is not available. You can use unix or "
35 "sensor_default. By default we replace your value by unix.");
42 ROS_INFO(
"Timestamp register in the header will be in the base time of : %s",
44 ROS_INFO(
"Use compensated acceleration : %s",
48 const std::string hardwareName = std::string{
"iXblue INS "} +
frame_id;
55 nh.
advertise<sensor_msgs::TimeReference>(
"standard/timereference", 1);
66 auto headerMsg =
getHeader(headerData, navData);
72 if(systemStatus2.test(
73 ixblue_stdbin_decoder::Data::INSSystemStatus::Status2::WAIT_FOR_POSITION))
89 timeReferenceMsg->header = headerMsg;
96 imuMsg->header = headerMsg;
102 navsatfixMsg->header = headerMsg;
107 iXinsMsg->header = headerMsg;
117 std_msgs::Header res;
134 boost::gregorian::date survey_day(navData.
systemDate.get().year,
139 boost::gregorian::date unix_origin(1970, 1, 1);
140 boost::posix_time::ptime survey_day_p = boost::posix_time::ptime(survey_day);
141 boost::posix_time::ptime unix_origin_p =
142 boost::posix_time::ptime(unix_origin);
143 uint32_t stamp_since_origin_sec =
144 (uint32_t)(survey_day_p - unix_origin_p).total_seconds();
147 res.stamp =
ros::Time(stamp_since_origin_sec + sec, nsec);
164 bool use_compensated_acceleration)
179 sensor_msgs::ImuPtr res = boost::make_shared<sensor_msgs::Imu>();
193 res->orientation_covariance.assign(0);
199 res->orientation_covariance[0] =
202 res->orientation_covariance[4] =
205 res->orientation_covariance[8] =
212 res->angular_velocity.x =
214 res->angular_velocity.y =
216 res->angular_velocity.z =
224 res->angular_velocity_covariance.assign(0);
230 res->angular_velocity_covariance[0] =
235 res->angular_velocity_covariance[4] =
240 res->angular_velocity_covariance[8] =
266 res->linear_acceleration_covariance.assign(0);
272 res->linear_acceleration_covariance[0] =
275 res->linear_acceleration_covariance[4] =
278 res->linear_acceleration_covariance[8] =
286 sensor_msgs::NavSatFixPtr
291 if(navData.
position.is_initialized() ==
false)
297 sensor_msgs::NavSatFixPtr res = boost::make_shared<sensor_msgs::NavSatFix>();
300 res->latitude = navData.
position.get().latitude_deg;
301 res->longitude = navData.
position.get().longitude_deg;
303 if(res->longitude > 180.0)
305 res->longitude -= 360.0;
307 res->altitude = navData.
position.get().altitude_m;
314 res->position_covariance.assign(0);
315 res->position_covariance_type = 0;
331 res->position_covariance[8] = navData.
positionDeviation.get().altitude_stddev_m *
333 res->position_covariance_type = 2;
339 sensor_msgs::TimeReferencePtr
343 sensor_msgs::TimeReferencePtr res = boost::make_shared<sensor_msgs::TimeReference>();
356 res->source = std::string(
"ins");
361 ixblue_ins_msgs::InsPtr
366 if(navData.
position.is_initialized() ==
false ||
375 ixblue_ins_msgs::InsPtr res = boost::make_shared<ixblue_ins_msgs::Ins>();
378 res->latitude = navData.
position.get().latitude_deg;
379 res->longitude = navData.
position.get().longitude_deg;
380 res->altitude_ref = navData.
position.get().altitude_ref;
381 res->altitude = navData.
position.get().altitude_m;
388 res->position_covariance.assign(0);
404 res->position_covariance[8] = navData.
positionDeviation.get().altitude_stddev_m *
418 res->attitude_covariance.assign(0);
424 res->attitude_covariance[0] =
427 res->attitude_covariance[4] =
430 res->attitude_covariance[8] =
445 res->speed_vessel_frame_covariance.assign(0);
451 res->speed_vessel_frame_covariance[0] =
454 res->speed_vessel_frame_covariance[4] =
457 res->speed_vessel_frame_covariance[8] =