mag.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020-2023 RaccoonLab.
3  *
4  * This program is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License as published by
6  * the Free Software Foundation, version 3.
7  *
8  * This program is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
11  * General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * Author: Dmitry Ponomarev <ponomarevda96@gmail.com>
17  */
18 
19 #include "mag.hpp"
20 #include <sensor_msgs/MagneticField.h>
21 #include "cs_converter.hpp"
22 
23 static const double MAG_NOISE = 0.0002;
24 
25 
26 MagSensor::MagSensor(ros::NodeHandle* nh, const char* topic, double period) : BaseSensor(nh, period){
27  publisher_ = node_handler_->advertise<sensor_msgs::MagneticField>(topic, 5);
28 }
29 bool MagSensor::publish(const Eigen::Vector3d& geoPosition, const Eigen::Quaterniond& attitudeFrdToNed) {
30  auto crntTimeSec = ros::Time::now().toSec();
31  if(!_isEnabled || (nextPubTimeSec_ > crntTimeSec)){
32  return false;
33  }
34 
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());
40  Eigen::Vector3d magFrd = attitudeFrdToNed.inverse() * Converter::enuToNed(magEnu);
41  msg.header.stamp = ros::Time();
42  msg.magnetic_field.x = magFrd[0] + MAG_NOISE * normalDistribution_(randomGenerator_);
43  msg.magnetic_field.y = magFrd[1] + MAG_NOISE * normalDistribution_(randomGenerator_);
44  msg.magnetic_field.z = magFrd[2] + MAG_NOISE * normalDistribution_(randomGenerator_);
45 
46  publisher_.publish(msg);
47  nextPubTimeSec_ = crntTimeSec + PERIOD;
48  return true;
49 }
double nextPubTimeSec_
Definition: sensor_base.hpp:37
Eigen::Vector3d enuToNed(Eigen::Vector3d enu)
bool publish(const Eigen::Vector3d &geoPosition, const Eigen::Quaterniond &attitudeFrdToNed)
Definition: mag.cpp:29
ros::NodeHandle * node_handler_
Definition: sensor_base.hpp:33
const double PERIOD
Definition: sensor_base.hpp:35
void publish(const boost::shared_ptr< M > &message) const
std::normal_distribution< double > normalDistribution_
Definition: sensor_base.hpp:40
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool _isEnabled
Definition: sensor_base.hpp:34
MagSensor(ros::NodeHandle *nh, const char *topic, double period)
Definition: mag.cpp:26
std::default_random_engine randomGenerator_
Definition: sensor_base.hpp:39
static Time now()
static const double MAG_NOISE
Definition: mag.cpp:23
ros::Publisher publisher_
Definition: sensor_base.hpp:36


inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Sat Jul 1 2023 02:13:44