Go to the documentation of this file.
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"
44 #include <boost/scoped_ptr.hpp>
61 return degrees * M_PI / 180.0;
95 std::string param_name = ns +
"/supported_imus/" + std::to_string(imu_type) +
"/" + name;
107 return std::stoi(rate);
124 std::string imu_desc;
142 ROS_ERROR_STREAM(
"Scale factors not supported for IMU '" << insconfig->imu_type <<
"'; raw IMU output disabled.");
149 "IMU: " << imu_type <<
" '" << imu_desc <<
"'"
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);
207 imu->orientation =
tf2::toMsg(tf_orientation);
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;
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;
234 static const double ZERO_DEGREES_AZIMUTH_OFFSET = 90.0;
235 double azimuth =
inspva_->azimuth - ZERO_DEGREES_AZIMUTH_OFFSET;
245 imu->orientation =
tf2::toMsg(tf_orientation);
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;
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;
303 ROS_WARN_THROTTLE(10,
"Unavailable or Invalid IMU rate and/or raw scale factors: %i %f %f",
372 ROS_WARN_STREAM(
"INS Reference Frame: using OEM7 (Y-forward) instead of REP105 (X-forward).");
379 static const std::vector<int> MSG_IDS(
void setup(const std::string &name, ros::NodeHandle &nh)
oem7_imu_type_t
IMUs supported on OEM7 products; refer to INSCONFIG in the OEM7 manual.
const ROSCPP_DECL std::string & getNamespace()
boost::shared_ptr< novatel_oem7_msgs::CORRIMU > corrimu_
Oem7RosPublisher inspvax_pub_
double computeAngularVelocityFromRaw(double raw_gyro)
#define ROS_ERROR_STREAM(args)
void handleMsg(Oem7RawMessageIf::ConstPtr msg)
void publishCorrImuMsg(Oem7RawMessageIf::ConstPtr msg)
double degreesToRadians(double degrees)
#define ROS_LOG_STREAM(level, name, args)
Oem7RosPublisher insstdev_pub_
const std::vector< int > & getMessageIds()
void processInsConfigMsg(Oem7RawMessageIf::ConstPtr msg)
bool getParam(const std::string &key, bool &b) const
#define ROS_FATAL_STREAM(args)
#define ROS_WARN_THROTTLE(period,...)
const int INSPVAX_OEM7_MSGID
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
double imu_raw_accel_scale_factor_
IMU-specific raw acceleration scaling.
void getImuDescription(oem7_imu_type_t imu_type, std::string &desc)
bool oem7_imu_reference_frame_
Backwards compatibility: use OEM7 reference frame, not compliant with REP105.
double computeLinearAccelerationFromRaw(double raw_acc)
void publishImuMsg_OEM7(boost::shared_ptr< sensor_msgs::Imu > &imu)
#define ROS_DEBUG_STREAM(args)
const int CORRIMUS_OEM7_MSGID
void publishInsStDevMsg(Oem7RawMessageIf::ConstPtr msg)
void getImuParam(oem7_imu_type_t imu_type, const std::string &name, std::string ¶m)
const int IMURATECORRIMUS_OEM7_MSGID
#define ROS_WARN_STREAM(args)
Oem7RosPublisher insconfig_pub_
double imu_raw_gyro_scale_factor_
IMU-specific raw gyroscope scaling.
PLUGINLIB_EXPORT_CLASS(novatel_oem7_driver::Oem7ConfigNodelet, nodelet::Nodelet)
const int RAWIMUSX_OEM7_MSGID
void publish(boost::shared_ptr< M > &msg)
const int INSCONFIG_OEM7_MSGID
void publishInsPVAXMsg(Oem7RawMessageIf::ConstPtr msg)
Oem7RosPublisher raw_imu_pub_
int imu_rate_t
IMU message output rate. Refer to INSCONFIG in the OEM7 manual.s.
int getImuRate(oem7_imu_type_t imu_type)
#define ROS_INFO_STREAM(args)
void publishImuMsg_ROS(boost::shared_ptr< sensor_msgs::Imu > &imu)
std::map< std::string, std::string > imu_config_map_t
void MakeROSMessage(const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< T > &rosmsg)
imu_rate_t imu_rate_
IMU output rate.
boost::shared_ptr< novatel_oem7_msgs::INSSTDEV > insstdev_
const double DATA_NOT_AVAILABLE
Used to initialized unpopulated fields.
bool getImuRawScaleFactors(oem7_imu_type_t imu_type, imu_rate_t imu_rate, double &gyro_scale, double &acc_scale)
const int INSSTDEV_OEM7_MSGID
const std::size_t OEM7_BINARY_MSG_SHORT_HDR_LEN
imu_config_map_t imu_config_map
T param(const std::string ¶m_name, const T &default_val)
void initialize(ros::NodeHandle &nh)
Oem7RosPublisher imu_pub_
#define ROSCONSOLE_DEFAULT_NAME
const int INSPVAS_OEM7_MSGID
Oem7RosPublisher corrimu_pub_
void processRawImuMsg(Oem7RawMessageIf::ConstPtr msg)
boost::shared_ptr< novatel_oem7_msgs::INSPVA > inspva_