15 #include <sensor_msgs/Temperature.h> 16 #include <sensor_msgs/RelativeHumidity.h> 28 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE) 30 #elif defined(TARGET_NUCLEO_F401RE) 33 #error "You need to specify a pin for the sensor" 45 long publisher_timer = 0;
46 temp_msg.header.frame_id =
"/base_link";
52 if (
t.read_ms() > publisher_timer)
54 error = sensor.readData();
65 publisher_timer =
t.read_ms() + 1000;
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher pub_temp("temperature",&temp_msg)
ros::Publisher pub_humidity("humidity",&humidity_msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
sensor_msgs::RelativeHumidity humidity_msg
sensor_msgs::Temperature temp_msg