Go to the documentation of this file.
20 #include <std_msgs/Float32.h>
34 std_msgs::Float32 msg;
35 msg.data = staticPressureHpa * 100;
52 std_msgs::Float32 msg;
53 msg.data = staticTemperature + 5;
std::normal_distribution< double > normalDistribution_
bool publish(float staticPressureHpa)
bool publish(float staticTemperature)
PressureSensor(ros::NodeHandle *nh, const char *topic, double period)
static const float STATIC_PRESSURE_NOISE
TemperatureSensor(ros::NodeHandle *nh, const char *topic, double period)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
std::default_random_engine randomGenerator_
ros::Publisher publisher_
static const float TEMPERATURE_NOISE
ros::NodeHandle * node_handler_
inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Mon Dec 9 2024 03:13:35