20 #include <sensor_msgs/MagneticField.h> 29 bool MagSensor::publish(
const Eigen::Vector3d& geoPosition,
const Eigen::Quaterniond& attitudeFrdToNed) {
35 sensor_msgs::MagneticField msg;
36 Eigen::Vector3d magEnu;
37 geographiclib_conversions::MagneticField(
38 geoPosition.x(), geoPosition.y(), geoPosition.z(),
39 magEnu.x(), magEnu.y(), magEnu.z());
Eigen::Vector3d enuToNed(Eigen::Vector3d enu)
bool publish(const Eigen::Vector3d &geoPosition, const Eigen::Quaterniond &attitudeFrdToNed)
ros::NodeHandle * node_handler_
void publish(const boost::shared_ptr< M > &message) const
std::normal_distribution< double > normalDistribution_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
MagSensor(ros::NodeHandle *nh, const char *topic, double period)
std::default_random_engine randomGenerator_
static const double MAG_NOISE
ros::Publisher publisher_