14 #include <std_msgs/Float32.h> 36 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE) 39 #error "You need to specify a pin for the sensor" 48 long publisher_timer =0;
52 if (
t.read_ms() > publisher_timer) {
66 temperature = ((msb) << 4);
67 temperature |= (lsb >> 4);
72 publisher_timer =
t.read_ms() + 1000;
void publish(const boost::shared_ptr< M > &message) const
std_msgs::Float32 temp_msg
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher pub_temp("temperature",&temp_msg)