ins_handler.cpp
Go to the documentation of this file.
1 //
3 // Copyright (c) 2020 NovAtel Inc.
4 //
5 // Permission is hereby granted, free of charge, to any person obtaining a copy
6 // of this software and associated documentation files (the "Software"), to deal
7 // in the Software without restriction, including without limitation the rights
8 // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 // copies of the Software, and to permit persons to whom the Software is
10 // furnished to do so, subject to the following conditions:
11 //
12 // The above copyright notice and this permission notice shall be included in all
13 // copies or substantial portions of the Software.
14 //
15 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 // SOFTWARE.
22 //
24 
26 
27 #include <ros/ros.h>
28 
29 
31 
35 
36 #include "sensor_msgs/Imu.h"
37 #include "novatel_oem7_msgs/CORRIMU.h"
38 #include "novatel_oem7_msgs/IMURATECORRIMU.h"
39 #include "novatel_oem7_msgs/INSSTDEV.h"
40 #include "novatel_oem7_msgs/INSCONFIG.h"
41 #include "novatel_oem7_msgs/INSPVA.h"
42 #include "novatel_oem7_msgs/INSPVAX.h"
43 
44 #include <boost/scoped_ptr.hpp>
45 #include <oem7_ros_publisher.hpp>
46 
47 #include <math.h>
48 #include <map>
49 
50 
51 
52 namespace novatel_oem7_driver
53 {
54  /***
55  * Converts degrees to Radians
56  *
57  * @return radians
58  */
59  inline double degreesToRadians(double degrees)
60  {
61  return degrees * M_PI / 180.0;
62  }
63 
64  const double DATA_NOT_AVAILABLE = -1.0;
65 
67  {
69 
76 
80 
84 
85  std::string frame_id_;
86 
87  typedef std::map<std::string, std::string> imu_config_map_t;
89 
91 
92  void getImuParam(oem7_imu_type_t imu_type, const std::string& name, std::string& param)
93  {
94  std::string ns = ros::this_node::getNamespace();
95  std::string param_name = ns + "/supported_imus/" + std::to_string(imu_type) + "/" + name;
96  if(!nh_.getParam(param_name, param))
97  {
98  ROS_FATAL_STREAM("INS: IMU type= " << imu_type << " is not supported.");
99  }
100  }
101 
103  {
104  std::string rate;
105  getImuParam(imu_type, "rate", rate);
106 
107  return std::stoi(rate);
108  }
109 
110  void getImuDescription(oem7_imu_type_t imu_type, std::string& desc)
111  {
112  getImuParam(imu_type, "name", desc);
113  }
114 
115 
116  void processInsConfigMsg(Oem7RawMessageIf::ConstPtr msg)
117  {
119  MakeROSMessage(msg, insconfig);
120  insconfig_pub_.publish(insconfig);
121 
122  oem7_imu_type_t imu_type = static_cast<oem7_imu_type_t>(insconfig->imu_type);
123 
124  std::string imu_desc;
125  getImuDescription(imu_type, imu_desc);
126 
127  if(imu_rate_ == 0)
128  {
129  imu_rate_ = getImuRate(imu_type);
130  }
131 
132  if(imu_raw_gyro_scale_factor_ == 0.0 &&
134  {
136  imu_type,
137  imu_rate_,
140 
141  {
142  ROS_ERROR_STREAM("Scale factors not supported for IMU '" << insconfig->imu_type << "'; raw IMU output disabled.");
143  }
144  }
145 
149  "IMU: " << imu_type << " '" << imu_desc << "'"
150  << " rate= " << imu_rate_
151  << " gyro scale= " << imu_raw_gyro_scale_factor_
152  << " accel scale= " << imu_raw_accel_scale_factor_);
153  }
154 
155  void publishInsPVAXMsg(Oem7RawMessageIf::ConstPtr msg)
156  {
158  MakeROSMessage(msg, inspvax);
159 
160  inspvax_pub_.publish(inspvax);
161  }
162 
163  void publishCorrImuMsg(Oem7RawMessageIf::ConstPtr msg)
164  {
165  MakeROSMessage(msg, corrimu_);
167  }
168 
169 
171  {
172  if(!imu_pub_.isEnabled())
173  {
174  return;
175  }
176 
177  boost::shared_ptr<sensor_msgs::Imu> imu(new sensor_msgs::Imu);
178 
180  {
181  publishImuMsg_OEM7(imu);
182  }
183  else
184  {
185  publishImuMsg_ROS(imu);
186  }
187 
188  if(insstdev_)
189  {
190  imu->orientation_covariance[0] = std::pow(insstdev_->roll_stdev, 2);
191  imu->orientation_covariance[4] = std::pow(insstdev_->pitch_stdev, 2);
192  imu->orientation_covariance[8] = std::pow(insstdev_->azimuth_stdev, 2);
193  }
194 
195  imu_pub_.publish(imu);
196  }
197 
199  {
200  if(inspva_)
201  {
202  tf2::Quaternion tf_orientation;
203  tf_orientation.setRPY(
204  degreesToRadians(inspva_->roll),
205  -degreesToRadians(inspva_->pitch),
206  -degreesToRadians(inspva_->azimuth));
207  imu->orientation = tf2::toMsg(tf_orientation);
208  }
209  else
210  {
211  ROS_WARN_THROTTLE(10, "INSPVA not available; 'Imu' message not generated.");
212  return;
213  }
214 
215  if(corrimu_ && corrimu_->imu_data_count && imu_rate_ > 0)
216  {
217  double instantaneous_rate_factor = imu_rate_ / corrimu_->imu_data_count;
218 
219  imu->angular_velocity.x = corrimu_->pitch_rate * instantaneous_rate_factor;
220  imu->angular_velocity.y = corrimu_->roll_rate * instantaneous_rate_factor;
221  imu->angular_velocity.z = corrimu_->yaw_rate * instantaneous_rate_factor;
222 
223  imu->linear_acceleration.x = corrimu_->lateral_acc * instantaneous_rate_factor;
224  imu->linear_acceleration.y = corrimu_->longitudinal_acc * instantaneous_rate_factor;
225  imu->linear_acceleration.z = corrimu_->vertical_acc * instantaneous_rate_factor;
226  }
227  }
228 
230  {
231  if(inspva_)
232  {
233  // Azimuth: Oem7 (North=0) to ROS (East=0), using Oem7 LH rule
234  static const double ZERO_DEGREES_AZIMUTH_OFFSET = 90.0;
235  double azimuth = inspva_->azimuth - ZERO_DEGREES_AZIMUTH_OFFSET;
236 
237  // Conversion to quaternion addresses rollover.
238  // Pitch and azimuth are adjusted from Y-forward, LH to X-forward, RH.
239  tf2::Quaternion tf_orientation;
240  tf_orientation.setRPY(
241  degreesToRadians(inspva_->roll),
242  -degreesToRadians(inspva_->pitch),
243  -degreesToRadians(azimuth));
244 
245  imu->orientation = tf2::toMsg(tf_orientation);
246  }
247  else
248  {
249  ROS_WARN_THROTTLE(10, "INSPVA not available; 'Imu' message not generated.");
250  return;
251  }
252 
253  if(corrimu_ && corrimu_->imu_data_count > 0 && imu_rate_ > 0)
254  {
255  double instantaneous_rate_factor = imu_rate_ / corrimu_->imu_data_count;
256 
257  imu->angular_velocity.x = corrimu_->roll_rate * instantaneous_rate_factor;
258  imu->angular_velocity.y = -corrimu_->pitch_rate * instantaneous_rate_factor;
259  imu->angular_velocity.z = corrimu_->yaw_rate * instantaneous_rate_factor;
260 
261  imu->linear_acceleration.x = corrimu_->longitudinal_acc * instantaneous_rate_factor;
262  imu->linear_acceleration.y = -corrimu_->lateral_acc * instantaneous_rate_factor;
263  imu->linear_acceleration.z = corrimu_->vertical_acc * instantaneous_rate_factor;
264  }
265  }
266 
267 
268  void publishInsStDevMsg(Oem7RawMessageIf::ConstPtr msg)
269  {
272  }
273 
274 
278  inline double computeAngularVelocityFromRaw(double raw_gyro)
279  {
280  return raw_gyro * imu_raw_gyro_scale_factor_ * imu_rate_;
281  }
282 
286  inline double computeLinearAccelerationFromRaw(double raw_acc)
287  {
288  return raw_acc * imu_raw_accel_scale_factor_ * imu_rate_;
289  }
290 
291 
292  void processRawImuMsg(Oem7RawMessageIf::ConstPtr msg)
293  {
294  if(!raw_imu_pub_.isEnabled())
295  {
296  return;
297  }
298 
299  if(imu_rate_ == 0 ||
302  {
303  ROS_WARN_THROTTLE(10, "Unavailable or Invalid IMU rate and/or raw scale factors: %i %f %f",
305 
306  return;
307  }
308 
309  const RAWIMUSXMem* raw = reinterpret_cast<const RAWIMUSXMem*>(msg->getMessageData(OEM7_BINARY_MSG_SHORT_HDR_LEN));
310  // All measurements are in sensor frame, uncorrected for gravity and Earth rotation. There is no up, forward, left;
311  // x, y, z are nominal references to enclosure housing.
312 
313  boost::shared_ptr<sensor_msgs::Imu> imu = boost::make_shared<sensor_msgs::Imu>();
314  imu->angular_velocity.x = computeAngularVelocityFromRaw(raw->x_gyro);
315  imu->angular_velocity.y = -computeAngularVelocityFromRaw(raw->y_gyro); // Refer to RAWIMUSX documentation
316  imu->angular_velocity.z = computeAngularVelocityFromRaw(raw->z_gyro);
317 
318  imu->linear_acceleration.x = computeLinearAccelerationFromRaw(raw->x_acc);
319  imu->linear_acceleration.y = -computeLinearAccelerationFromRaw(raw->y_acc); // Refer to RASIMUSX documentation
320  imu->linear_acceleration.z = computeLinearAccelerationFromRaw(raw->z_acc);
321 
322  imu->orientation_covariance[0] = DATA_NOT_AVAILABLE;
323 
324  raw_imu_pub_.publish(imu);
325  }
326 
327 
328  public:
330  imu_rate_(0),
334  {
335  }
336 
338  {
339  }
340 
342  {
343  nh_ = nh;
344 
345  imu_pub_.setup<sensor_msgs::Imu>( "IMU", nh);
346  raw_imu_pub_.setup<sensor_msgs::Imu>( "RAWIMU", nh);
347  corrimu_pub_.setup< novatel_oem7_msgs::CORRIMU>( "CORRIMU", nh);
348  insstdev_pub_.setup< novatel_oem7_msgs::INSSTDEV>( "INSSTDEV", nh);
349  inspvax_pub_.setup< novatel_oem7_msgs::INSPVAX>( "INSPVAX", nh);
350  insconfig_pub_.setup<novatel_oem7_msgs::INSCONFIG>("INSCONFIG", nh);
351 
352  // User overrides for IMU
353  nh.getParam("imu_rate", imu_rate_);
354  nh.getParam("imu_gyro_scale_factor", imu_raw_gyro_scale_factor_);
355  nh.getParam("imu_accel_scale_factor", imu_raw_accel_scale_factor_);
356  if(imu_rate_ != 0 ||
359  {
360  ROS_INFO_STREAM("INS: IMU config overrides to rate= " << imu_rate_
361  << " gyro scale factor= " << imu_raw_gyro_scale_factor_
362  << " accel scale factor= " << imu_raw_accel_scale_factor_);
363  }
364 
365 
366 
367 
368  if(!nh_.getParam("oem7_imu_reference_frame", oem7_imu_reference_frame_))
369  {
371  {
372  ROS_WARN_STREAM("INS Reference Frame: using OEM7 (Y-forward) instead of REP105 (X-forward).");
373  }
374  }
375  }
376 
377  const std::vector<int>& getMessageIds()
378  {
379  static const std::vector<int> MSG_IDS(
380  {
388  }
389  );
390  return MSG_IDS;
391  }
392 
393  void handleMsg(Oem7RawMessageIf::ConstPtr msg)
394  {
395  ROS_DEBUG_STREAM("INS < [id= " << msg->getMessageId() << "]");
396 
397  if(msg->getMessageId()== INSPVAS_OEM7_MSGID)
398  {
399  MakeROSMessage(msg, inspva_); // Cache
400  }
401  else if(msg->getMessageId() == INSSTDEV_OEM7_MSGID)
402  {
403  publishInsStDevMsg(msg);
404  }
405  else if(msg->getMessageId() == CORRIMUS_OEM7_MSGID ||
406  msg->getMessageId() == IMURATECORRIMUS_OEM7_MSGID)
407  {
408  publishCorrImuMsg(msg);
409 
410  publishImuMsg();
411  }
412  else if(msg->getMessageId() == INSCONFIG_OEM7_MSGID)
413  {
414  processInsConfigMsg(msg);
415  }
416  else if(msg->getMessageId() == INSPVAX_OEM7_MSGID)
417  {
418  publishInsPVAXMsg(msg);
419  }
420  else if(msg->getMessageId() == RAWIMUSX_OEM7_MSGID)
421  {
422  processRawImuMsg(msg);
423  }
424  else
425  {
426  assert(false);
427  }
428  }
429  };
430 
431 }
432 
novatel_oem7_driver::Oem7RosPublisher::setup
void setup(const std::string &name, ros::NodeHandle &nh)
Definition: oem7_ros_publisher.hpp:47
novatel_oem7_driver::oem7_imu_type_t
oem7_imu_type_t
IMUs supported on OEM7 products; refer to INSCONFIG in the OEM7 manual.
Definition: oem7_imu.hpp:29
novatel_oem7_driver::INSHandler
Definition: ins_handler.cpp:66
ros::this_node::getNamespace
const ROSCPP_DECL std::string & getNamespace()
novatel_oem7_driver::INSHandler::corrimu_
boost::shared_ptr< novatel_oem7_msgs::CORRIMU > corrimu_
Definition: ins_handler.cpp:78
novatel_oem7_driver::INSHandler::inspvax_pub_
Oem7RosPublisher inspvax_pub_
Definition: ins_handler.cpp:74
novatel_oem7_driver::Oem7RosPublisher::isEnabled
bool isEnabled()
Definition: oem7_ros_publisher.hpp:83
ros::console::levels::Error
Error
novatel_oem7_driver::INSHandler::computeAngularVelocityFromRaw
double computeAngularVelocityFromRaw(double raw_gyro)
Definition: ins_handler.cpp:278
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
boost::shared_ptr< novatel_oem7_msgs::INSPVA >
novatel_oem7_driver::INSHandler::handleMsg
void handleMsg(Oem7RawMessageIf::ConstPtr msg)
Definition: ins_handler.cpp:393
novatel_oem7_driver::INSHandler::publishCorrImuMsg
void publishCorrImuMsg(Oem7RawMessageIf::ConstPtr msg)
Definition: ins_handler.cpp:163
novatel_oem7_driver::degreesToRadians
double degreesToRadians(double degrees)
Definition: bestpos_handler.cpp:84
ROS_LOG_STREAM
#define ROS_LOG_STREAM(level, name, args)
novatel_oem7_driver::INSHandler::insstdev_pub_
Oem7RosPublisher insstdev_pub_
Definition: ins_handler.cpp:73
novatel_oem7_driver::INSHandler::~INSHandler
~INSHandler()
Definition: ins_handler.cpp:337
novatel_oem7_driver::INSHandler::getMessageIds
const std::vector< int > & getMessageIds()
Definition: ins_handler.cpp:377
novatel_oem7_driver::INSHandler::processInsConfigMsg
void processInsConfigMsg(Oem7RawMessageIf::ConstPtr msg)
Definition: ins_handler.cpp:116
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ROS_FATAL_STREAM
#define ROS_FATAL_STREAM(args)
ROS_WARN_THROTTLE
#define ROS_WARN_THROTTLE(period,...)
ros.h
oem7_ros_messages.hpp
novatel_oem7_driver::INSPVAX_OEM7_MSGID
const int INSPVAX_OEM7_MSGID
Definition: oem7_message_ids.h:47
tf2::Quaternion::setRPY
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
novatel_oem7_driver::INSHandler::imu_raw_accel_scale_factor_
double imu_raw_accel_scale_factor_
IMU-specific raw acceleration scaling.
Definition: ins_handler.cpp:83
novatel_oem7_driver::INSHandler::getImuDescription
void getImuDescription(oem7_imu_type_t imu_type, std::string &desc)
Definition: ins_handler.cpp:110
novatel_oem7_driver::INSHandler::oem7_imu_reference_frame_
bool oem7_imu_reference_frame_
Backwards compatibility: use OEM7 reference frame, not compliant with REP105.
Definition: ins_handler.cpp:90
novatel_oem7_driver::INSHandler::computeLinearAccelerationFromRaw
double computeLinearAccelerationFromRaw(double raw_acc)
Definition: ins_handler.cpp:286
novatel_oem7_driver::INSHandler::publishImuMsg_OEM7
void publishImuMsg_OEM7(boost::shared_ptr< sensor_msgs::Imu > &imu)
Definition: ins_handler.cpp:198
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
novatel_oem7_driver::CORRIMUS_OEM7_MSGID
const int CORRIMUS_OEM7_MSGID
Definition: oem7_message_ids.h:42
novatel_oem7_driver::INSHandler::publishInsStDevMsg
void publishInsStDevMsg(Oem7RawMessageIf::ConstPtr msg)
Definition: ins_handler.cpp:268
novatel_oem7_driver::INSHandler::nh_
ros::NodeHandle nh_
Definition: ins_handler.cpp:68
novatel_oem7_driver::INSHandler::getImuParam
void getImuParam(oem7_imu_type_t imu_type, const std::string &name, std::string &param)
Definition: ins_handler.cpp:92
novatel_oem7_driver::IMURATECORRIMUS_OEM7_MSGID
const int IMURATECORRIMUS_OEM7_MSGID
Definition: oem7_message_ids.h:44
class_list_macros.h
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
oem7_imu.hpp
novatel_oem7_driver::INSHandler::insconfig_pub_
Oem7RosPublisher insconfig_pub_
Definition: ins_handler.cpp:75
novatel_oem7_driver::INSHandler::imu_raw_gyro_scale_factor_
double imu_raw_gyro_scale_factor_
IMU-specific raw gyroscope scaling.
Definition: ins_handler.cpp:82
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(novatel_oem7_driver::Oem7ConfigNodelet, nodelet::Nodelet)
novatel_oem7_driver::RAWIMUSX_OEM7_MSGID
const int RAWIMUSX_OEM7_MSGID
Definition: oem7_message_ids.h:52
novatel_oem7_driver::Oem7RosPublisher::publish
void publish(boost::shared_ptr< M > &msg)
Definition: oem7_ros_publisher.hpp:92
novatel_oem7_driver::INSCONFIG_OEM7_MSGID
const int INSCONFIG_OEM7_MSGID
Definition: oem7_message_ids.h:45
novatel_oem7_driver::INSHandler::publishInsPVAXMsg
void publishInsPVAXMsg(Oem7RawMessageIf::ConstPtr msg)
Definition: ins_handler.cpp:155
oem7_message_handler_if.hpp
novatel_oem7_driver::INSHandler::raw_imu_pub_
Oem7RosPublisher raw_imu_pub_
Definition: ins_handler.cpp:71
novatel_oem7_driver::imu_rate_t
int imu_rate_t
IMU message output rate. Refer to INSCONFIG in the OEM7 manual.s.
Definition: oem7_imu.hpp:59
novatel_oem7_driver::INSHandler::getImuRate
int getImuRate(oem7_imu_type_t imu_type)
Definition: ins_handler.cpp:102
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
novatel_oem7_driver::INSHandler::publishImuMsg_ROS
void publishImuMsg_ROS(boost::shared_ptr< sensor_msgs::Imu > &imu)
Definition: ins_handler.cpp:229
ros::console::levels::Info
Info
novatel_oem7_driver::INSHandler::imu_config_map_t
std::map< std::string, std::string > imu_config_map_t
Definition: ins_handler.cpp:87
novatel_oem7_driver::MakeROSMessage
void MakeROSMessage(const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< T > &rosmsg)
novatel_oem7_driver::INSHandler::imu_rate_
imu_rate_t imu_rate_
IMU output rate.
Definition: ins_handler.cpp:81
novatel_oem7_driver::Oem7RosPublisher
Definition: oem7_ros_publisher.hpp:38
novatel_oem7_driver::INSHandler::insstdev_
boost::shared_ptr< novatel_oem7_msgs::INSSTDEV > insstdev_
Definition: ins_handler.cpp:79
novatel_oem7_driver::DATA_NOT_AVAILABLE
const double DATA_NOT_AVAILABLE
Used to initialized unpopulated fields.
Definition: ins_handler.cpp:64
novatel_oem7_driver::getImuRawScaleFactors
bool getImuRawScaleFactors(oem7_imu_type_t imu_type, imu_rate_t imu_rate, double &gyro_scale, double &acc_scale)
Definition: oem7_imu.cpp:61
novatel_oem7_driver::INSSTDEV_OEM7_MSGID
const int INSSTDEV_OEM7_MSGID
Definition: oem7_message_ids.h:48
novatel_oem7_driver::INSHandler::INSHandler
INSHandler()
Definition: ins_handler.cpp:329
novatel_oem7_driver::OEM7_BINARY_MSG_SHORT_HDR_LEN
const std::size_t OEM7_BINARY_MSG_SHORT_HDR_LEN
Definition: oem7_messages.h:513
novatel_oem7_driver::INSHandler::imu_config_map
imu_config_map_t imu_config_map
Definition: ins_handler.cpp:88
oem7_messages.h
tf2::Quaternion
tf2_geometry_msgs.h
tf2::toMsg
B toMsg(const A &a)
param
T param(const std::string &param_name, const T &default_val)
novatel_oem7_driver::INSHandler::initialize
void initialize(ros::NodeHandle &nh)
Definition: ins_handler.cpp:341
novatel_oem7_driver::INSHandler::imu_pub_
Oem7RosPublisher imu_pub_
Definition: ins_handler.cpp:70
ROSCONSOLE_DEFAULT_NAME
#define ROSCONSOLE_DEFAULT_NAME
novatel_oem7_driver::INSPVAS_OEM7_MSGID
const int INSPVAS_OEM7_MSGID
Definition: oem7_message_ids.h:46
novatel_oem7_driver::INSHandler::corrimu_pub_
Oem7RosPublisher corrimu_pub_
Definition: ins_handler.cpp:72
novatel_oem7_driver::INSHandler::frame_id_
std::string frame_id_
Definition: ins_handler.cpp:85
novatel_oem7_driver::Oem7MessageHandlerIf
Definition: oem7_message_handler_if.hpp:41
novatel_oem7_driver
Definition: oem7_imu.hpp:25
novatel_oem7_driver::INSHandler::processRawImuMsg
void processRawImuMsg(Oem7RawMessageIf::ConstPtr msg)
Definition: ins_handler.cpp:292
novatel_oem7_driver::INSHandler::publishImuMsg
void publishImuMsg()
Definition: ins_handler.cpp:170
novatel_oem7_driver::INSHandler::inspva_
boost::shared_ptr< novatel_oem7_msgs::INSPVA > inspva_
Definition: ins_handler.cpp:77
ros::NodeHandle
oem7_ros_publisher.hpp


novatel_oem7_driver
Author(s):
autogenerated on Sat Feb 3 2024 03:51:34