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 #include "UavDynamics/math/wmm.hpp"
23 
24 static const double MAG_NOISE = 0.0002;
25 
26 
27 MagSensor::MagSensor(ros::NodeHandle* nh, const char* topic, double period) : BaseSensor(nh, period){
28  publisher_ = node_handler_->advertise<sensor_msgs::MagneticField>(topic, 5);
29 }
30 bool MagSensor::publish(const Eigen::Vector3d& geoPosition, const Eigen::Quaterniond& attitudeFrdToNed) {
31  auto crntTimeSec = ros::Time::now().toSec();
32  if(!_isEnabled || (nextPubTimeSec_ > crntTimeSec)){
33  return false;
34  }
35 
36  sensor_msgs::MagneticField msg;
37  Eigen::Vector3d magEnu;
39  geoPosition.x(), geoPosition.y(), geoPosition.z(),
40  magEnu.x(), magEnu.y(), magEnu.z()
41  );
42 
43  magEnu.z() = -1 * magEnu.z();
44 
45  Eigen::Vector3d magFrd = attitudeFrdToNed.inverse() * Converter::enuToNed(magEnu);
46  msg.header.stamp = ros::Time();
47  msg.magnetic_field.x = magFrd[0] + MAG_NOISE * normalDistribution_(randomGenerator_);
48  msg.magnetic_field.y = magFrd[1] + MAG_NOISE * normalDistribution_(randomGenerator_);
49  msg.magnetic_field.z = magFrd[2] + MAG_NOISE * normalDistribution_(randomGenerator_);
50 
51  publisher_.publish(msg);
52  nextPubTimeSec_ = crntTimeSec + PERIOD;
53  return true;
54 }
BaseSensor::normalDistribution_
std::normal_distribution< double > normalDistribution_
Definition: sensor_base.hpp:39
MagSensor::MagSensor
MagSensor(ros::NodeHandle *nh, const char *topic, double period)
Definition: mag.cpp:27
calculateMagneticFieldStrengthGauss
void calculateMagneticFieldStrengthGauss(const double lat, const double lon, const double alt, double &mag_east_gauss, double &mag_north_gauss, double &mag_up_gauss)
Definition: wmm.cpp:126
BaseSensor::_isEnabled
bool _isEnabled
Definition: sensor_base.hpp:33
wmm.hpp
TimeBase< Time, Duration >::toSec
double toSec() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
mag.hpp
BaseSensor::randomGenerator_
std::default_random_engine randomGenerator_
Definition: sensor_base.hpp:38
BaseSensor::publisher_
ros::Publisher publisher_
Definition: sensor_base.hpp:35
BaseSensor::nextPubTimeSec_
double nextPubTimeSec_
Definition: sensor_base.hpp:36
MAG_NOISE
static const double MAG_NOISE
Definition: mag.cpp:24
ros::Time
MagSensor::publish
bool publish(const Eigen::Vector3d &geoPosition, const Eigen::Quaterniond &attitudeFrdToNed)
Definition: mag.cpp:30
BaseSensor::PERIOD
const double PERIOD
Definition: sensor_base.hpp:34
BaseSensor
Definition: sensor_base.hpp:25
BaseSensor::node_handler_
ros::NodeHandle * node_handler_
Definition: sensor_base.hpp:32
Converter::enuToNed
Eigen::Vector3d enuToNed(Eigen::Vector3d enu)
Definition: cs_converter.cpp:53
ros::NodeHandle
cs_converter.hpp
ros::Time::now
static Time now()


inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Mon Dec 9 2024 03:13:35