imu.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 "imu.hpp"
20 #include <sensor_msgs/Imu.h>
21 
22 
23 ImuSensor::ImuSensor(ros::NodeHandle* nh, const char* topic, double period) : BaseSensor(nh, period){
24  publisher_ = node_handler_->advertise<sensor_msgs::Imu>(topic, 5);
25 }
26 bool ImuSensor::publish(const Eigen::Vector3d& accFrd, const Eigen::Vector3d& gyroFrd) {
27  auto crntTimeSec = ros::Time::now().toSec();
28  if(!_isEnabled || (nextPubTimeSec_ > crntTimeSec)){
29  return false;
30  }
31 
32  sensor_msgs::Imu msg;
33  msg.header.stamp = ros::Time::now();
34  msg.angular_velocity.x = gyroFrd[0];
35  msg.angular_velocity.y = gyroFrd[1];
36  msg.angular_velocity.z = gyroFrd[2];
37  msg.linear_acceleration.x = accFrd[0];
38  msg.linear_acceleration.y = accFrd[1];
39  msg.linear_acceleration.z = accFrd[2];
40 
41  publisher_.publish(msg);
42  if (nextPubTimeSec_ + PERIOD > crntTimeSec) {
44  } else {
45  nextPubTimeSec_ = crntTimeSec + PERIOD;
46  }
47  return true;
48 }
double nextPubTimeSec_
Definition: sensor_base.hpp:37
ImuSensor(ros::NodeHandle *nh, const char *topic, double period)
Definition: imu.cpp:23
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
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool _isEnabled
Definition: sensor_base.hpp:34
bool publish(const Eigen::Vector3d &accFrd, const Eigen::Vector3d &gyroFrd)
Definition: imu.cpp:26
static Time now()
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