-
Notifications
You must be signed in to change notification settings - Fork 34
Open
Description
Hi! Just curious if this repo is still under maintenance?
I noticed that novatel_node.cpp uses tf::createQuaternionMsgFromRollPitchYaw to handle attitude angle roll/pitch/azimuth. tf::createQuaternionMsgFromRollPitchYaw assumes roll is around x and pitch around y. However, according to novatel manuals, in e.g. the PVA log, roll is around y and pitch around x. Azimuth is around z but left-hand rotated. So suggested to change the code to
Eigen::Quaterniond quat(Eigen::AngleAxisd(-ins_pva.azimuth * degrees_to_radians, Eigen::Vector3d::UnitZ()) *
Eigen::AngleAxisd(ins_pva.pitch * degrees_to_radians, Eigen::Vector3d::UnitX()) *
Eigen::AngleAxisd(ins_pva.roll * degrees_to_radians, Eigen::Vector3d::UnitY()));
tf::quaternionEigenToMsg(quat, cur_odom_.pose.pose.orientation);
Metadata
Metadata
Assignees
Labels
No labels