attitude.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 "attitude.hpp"
20 #include <geometry_msgs/QuaternionStamped.h>
21 
22 
23 AttitudeSensor::AttitudeSensor(ros::NodeHandle* nh, const char* topic, double period) : BaseSensor(nh, period){
24  publisher_ = node_handler_->advertise<geometry_msgs::QuaternionStamped>(topic, 5);
25 }
26 bool AttitudeSensor::publish(const Eigen::Quaterniond& attitudeFrdToNed) {
27  auto crntTimeSec = ros::Time::now().toSec();
28  if(!_isEnabled || (nextPubTimeSec_ > crntTimeSec)){
29  return false;
30  }
31 
32  geometry_msgs::QuaternionStamped msg;
33  msg.quaternion.x = attitudeFrdToNed.x();
34  msg.quaternion.y = attitudeFrdToNed.y();
35  msg.quaternion.z = attitudeFrdToNed.z();
36  msg.quaternion.w = attitudeFrdToNed.w();
37  msg.header.stamp = ros::Time::now();
38 
39  publisher_.publish(msg);
40  nextPubTimeSec_ = crntTimeSec + PERIOD;
41  return true;
42 }
BaseSensor::_isEnabled
bool _isEnabled
Definition: sensor_base.hpp:33
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)
BaseSensor::publisher_
ros::Publisher publisher_
Definition: sensor_base.hpp:35
BaseSensor::nextPubTimeSec_
double nextPubTimeSec_
Definition: sensor_base.hpp:36
AttitudeSensor::AttitudeSensor
AttitudeSensor(ros::NodeHandle *nh, const char *topic, double period)
Definition: attitude.cpp:23
AttitudeSensor::publish
bool publish(const Eigen::Quaterniond &attitudeFrdToNed)
Definition: attitude.cpp:26
attitude.hpp
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
ros::NodeHandle
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